move3d_ros_lib
0.1.0
move3d/ros API interface
|
The SceneManager class provide interface between ROS and the move3d scene and project. Use it to start libmove3d and place the robots and objects in the environment. More...
#include <scenemanager.h>
Public Member Functions | |
SceneManager (ros::NodeHandle *nh) | |
default constructor More... | |
SceneManager (ros::NodeHandle *nh, const std::string &p3d_path) | |
SceneManager. More... | |
bool | addModule (const std::string &name) |
add a move3d module to be initialized More... | |
bool | createScene () |
create the move3d scene and project. More... | |
bool | updateRobotPose (const std::string &name, const geometry_msgs::Pose &base_pose) |
update the base pose of a robot (any moveable obect). More... | |
bool | updateRobot (const std::string &name, const geometry_msgs::Pose &base_pose, const std::vector< double > &dof_values) |
update a robot configuration (any moveable object). More... | |
bool | updateRobotM3d (const std::string &name, std::vector< double > &dof_values) |
update a robot configuration (any moveable object). More... | |
bool | updateObject (const std::string &name, const geometry_msgs::Pose &pose) |
as updateRobotPose(string,Pose) | |
bool | updateHuman (const std::string &name, const geometry_msgs::Pose &base_pose, const std::map< std::string, geometry_msgs::Pose > &joints) |
updatea human position More... | |
void | setDofCorresp (const std::string &robot_name, const std::map< std::string, std::string > &ros_to_move3d_map) |
set the matching of ROS DoF names and move3d ones. More... | |
bool | setDofNameOrdered (const std::string &robot_name, const std::vector< std::string > &dof_names) |
set the DoF order as it will be when calling any updateRobot method. More... | |
bool | fetchDofCorrespParam (const std::string ¶m_name, const std::string &robot_name) |
retrieve map of joint/dof correspondances More... | |
bool | fetchDofCorrespParam (const std::string &base_param_name) |
retrieve map of joint/dof correspondances for all robots More... | |
bool | convertConfRosToM3d (const std::string &robot_name, const std::vector< double > &ros_conf, std::vector< double > &m3d_conf) |
convert a configuration from ROS to move3d. Only changes joint order, and remove joints that do not exist in Move3d. More... | |
std::string | p3dPath () const |
get the path to the p3d file. More... | |
void | setP3dPath (const std::string &p3dPath) |
set the path to the p3d file used to describe the environment and its robots and objects. More... | |
std::string | scePath () const |
void | setScePath (const std::string &scePath) |
set the path to a sce file to load on startup More... | |
bool | saveScenario (const std::string &path) |
save the scenario, ie. the positions and configurations of all objects and robots More... | |
Eigen::Affine3d | getFrameTransform () const |
void | setFrameTransform (const Eigen::Affine3d &frame_change) |
bool | updateAcceptBaseOnly () const |
updateAcceptBaseOnly indicates the possibility to consider only the base position of an agent. More... | |
void | setUpdateAcceptBaseOnly (bool updateAcceptBaseOnly) |
setUpdateAcceptBaseOnly More... | |
Project * | project () const |
get the move3d project object More... | |
void | setProject (Project *project) |
set a project instead of creating it with createScene More... | |
ros::NodeHandle * | nh () const |
get the node handle | |
void | setNh (ros::NodeHandle *nh) |
set the node handle | |
The SceneManager class provide interface between ROS and the move3d scene and project. Use it to start libmove3d and place the robots and objects in the environment.
move3d::SceneManager::SceneManager | ( | ros::NodeHandle * | nh | ) |
default constructor
nh |
move3d::SceneManager::SceneManager | ( | ros::NodeHandle * | nh, |
const std::string & | p3d_path | ||
) |
nh | |
p3d_path |
bool move3d::SceneManager::addModule | ( | const std::string & | name | ) |
add a move3d module to be initialized
name | name of the module |
The project must be NOT initialized, otherwise does nothing and return false. So you need to call this BEFORE calling createScene()
bool move3d::SceneManager::convertConfRosToM3d | ( | const std::string & | robot_name, |
const std::vector< double > & | ros_conf, | ||
std::vector< double > & | m3d_conf | ||
) |
convert a configuration from ROS to move3d. Only changes joint order, and remove joints that do not exist in Move3d.
[in] | robot_name | |
[in] | ros_conf | |
[out] | m3d_conf |
bool move3d::SceneManager::createScene | ( | ) |
create the move3d scene and project.
A path to a p3d file must be given in the constructor or with setP3dPath(). To add a module, you need to call addModule() before createScene(). This is required in order to use most of the components of move3d.
bool move3d::SceneManager::fetchDofCorrespParam | ( | const std::string & | param_name, |
const std::string & | robot_name | ||
) |
retrieve map of joint/dof correspondances
param_name | where the dictionnary is located in the ROS parameter server |
robot_name | the (complete) name of the robot in move3d |
The dictionnary in ROS parameters have the form:
So as an example, you could put in a .yaml file to load:
bool move3d::SceneManager::fetchDofCorrespParam | ( | const std::string & | base_param_name | ) |
retrieve map of joint/dof correspondances for all robots
base_param_name | where the dictionnaries are located in the ROS parameter server |
For each robot agent in the scenes, it tries to find a dictionnary of joint names correspondances under base_param_name/<robot_type>, and if not found, under base_param_name/<robot_name>.
Eigen::Affine3d move3d::SceneManager::getFrameTransform | ( | ) | const |
std::string move3d::SceneManager::p3dPath | ( | ) | const |
get the path to the p3d file.
Project * move3d::SceneManager::project | ( | ) | const |
get the move3d project object
bool move3d::SceneManager::saveScenario | ( | const std::string & | path | ) |
save the scenario, ie. the positions and configurations of all objects and robots
path | the path where to save the scenario |
std::string move3d::SceneManager::scePath | ( | ) | const |
void move3d::SceneManager::setDofCorresp | ( | const std::string & | robot_name, |
const std::map< std::string, std::string > & | ros_to_move3d_map | ||
) |
bool move3d::SceneManager::setDofNameOrdered | ( | const std::string & | robot_name, |
const std::vector< std::string > & | dof_names | ||
) |
set the DoF order as it will be when calling any updateRobot method.
robot_name | the name of the robot |
dof_names | the vector of dof names that will be given to updateRobot for that robot |
void move3d::SceneManager::setFrameTransform | ( | const Eigen::Affine3d & | frame_change | ) |
void move3d::SceneManager::setP3dPath | ( | const std::string & | p3dPath | ) |
set the path to the p3d file used to describe the environment and its robots and objects.
p3dPath | the path prefer absolute paths or ROS package:// url |
void move3d::SceneManager::setProject | ( | Project * | project | ) |
set a project instead of creating it with createScene
project | a move3d project |
void move3d::SceneManager::setScePath | ( | const std::string & | scePath | ) |
set the path to a sce file to load on startup
scePath | the path prefer absolute paths or ROS package:// url |
void move3d::SceneManager::setUpdateAcceptBaseOnly | ( | bool | updateAcceptBaseOnly | ) |
bool move3d::SceneManager::updateAcceptBaseOnly | ( | ) | const |
updateAcceptBaseOnly indicates the possibility to consider only the base position of an agent.
When True, calls to updateRobot with empty dof_values will result in the same as calling updateRobotPose. Otherwise the robot is not updated.
bool move3d::SceneManager::updateHuman | ( | const std::string & | name, |
const geometry_msgs::Pose & | base_pose, | ||
const std::map< std::string, geometry_msgs::Pose > & | joints | ||
) |
updatea human position
name | name of the human in ROS |
base_pose | position of the base joint of the human |
joints | other joint positions (not configuration) in an absolute frame |
bool move3d::SceneManager::updateRobot | ( | const std::string & | name, |
const geometry_msgs::Pose & | base_pose, | ||
const std::vector< double > & | dof_values | ||
) |
update a robot configuration (any moveable object).
name | name of the robot to place |
base_pose | the base pose (pose of the 1st joint) |
dof_values | values of the other degrees of freedom (ordered as in ROS) |
bool move3d::SceneManager::updateRobotM3d | ( | const std::string & | name, |
std::vector< double > & | dof_values | ||
) |
update a robot configuration (any moveable object).
name | name of the robot to place |
dof_values | value of all the degrees of freedom (ordered as in move3d) |
bool move3d::SceneManager::updateRobotPose | ( | const std::string & | name, |
const geometry_msgs::Pose & | base_pose | ||
) |
update the base pose of a robot (any moveable obect).
name | name of the robot/object |
base_pose | the pose where to place the robot |