move3d_ros_lib  0.1.0
move3d/ros API interface
 All Classes Namespaces Functions Variables Typedefs Pages
Public Types | Public Member Functions | List of all members
move3d::SceneManager Class Reference

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 Types

typedef std::map< std::string,
std::string > 
NameMap_t
 
typedef std::map< uint, uint > UintMap_t
 
typedef std::map< std::string,
NameMap_t > 
JointCorrespName_t
 
typedef std::map< std::string,
UintMap_t > 
JointCorrespIndex_t
 

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 &param_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
 

Detailed Description

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.

Constructor & Destructor Documentation

move3d::SceneManager::SceneManager ( ros::NodeHandle *  nh)

default constructor

Parameters
nh
move3d::SceneManager::SceneManager ( ros::NodeHandle *  nh,
const std::string &  p3d_path 
)

SceneManager.

Parameters
nh
p3d_path

Member Function Documentation

bool move3d::SceneManager::addModule ( const std::string &  name)

add a move3d module to be initialized

Parameters
namename of the module
Returns
true on success, false otherwise.

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.

Parameters
[in]robot_name
[in]ros_conf
[out]m3d_conf
Returns
false on error
bool move3d::SceneManager::createScene ( )

create the move3d scene and project.

Returns
false on error

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.

See Also
setProject allows to set a already initialized project
bool move3d::SceneManager::fetchDofCorrespParam ( const std::string &  param_name,
const std::string &  robot_name 
)

retrieve map of joint/dof correspondances

Parameters
param_namewhere the dictionnary is located in the ROS parameter server
robot_namethe (complete) name of the robot in move3d
Returns
false if the project is not correctly initialized. Empty or non-existent map is ok.

The dictionnary in ROS parameters have the form:

param_name : {
ros_joint_name: move3d_joint_name,
}

So as an example, you could put in a .yaml file to load:

---
move3d:
dof_name_corresp: {
PR2_ROBOT: {
torso_lift_link: Torso,
head_pan_link: pan_cam,
head_tilt_link: tilt_cam,
...
}
}
bool move3d::SceneManager::fetchDofCorrespParam ( const std::string &  base_param_name)

retrieve map of joint/dof correspondances for all robots

Parameters
base_param_namewhere the dictionnaries are located in the ROS parameter server
Returns
false if the project is not correctly initialized. Empty or non-existent map is ok.

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>.

See Also
SceneManager::fetchDofCorrespParam(const std::string&, const std::string&)
Eigen::Affine3d move3d::SceneManager::getFrameTransform ( ) const
Todo:
not implemented
std::string move3d::SceneManager::p3dPath ( ) const

get the path to the p3d file.

Returns
the path
Project * move3d::SceneManager::project ( ) const

get the move3d project object

Returns
bool move3d::SceneManager::saveScenario ( const std::string &  path)

save the scenario, ie. the positions and configurations of all objects and robots

Parameters
paththe path where to save the scenario
Returns
true on success The created scenario (.sce) is compatible with any move3d instance, as move3d-studio.
std::string move3d::SceneManager::scePath ( ) const
See Also
setScePath
void move3d::SceneManager::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.

Parameters
robot_namethe name of the robot
ros_to_move3d_mapkeys are the name of the joints in ROS, values are the corresponding names in move3d.
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.

Parameters
robot_namethe name of the robot
dof_namesthe vector of dof names that will be given to updateRobot for that robot
Returns
This allows the updateRobot methods to avoid parsing strings at every call. It is required to call this method after setDofCorresp and BEFORE any call to updateRobot() with the same robot_name.
void move3d::SceneManager::setFrameTransform ( const Eigen::Affine3d &  frame_change)
Todo:
not implemented
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.

Parameters
p3dPaththe path prefer absolute paths or ROS package:// url
void move3d::SceneManager::setProject ( Project *  project)

set a project instead of creating it with createScene

Parameters
projecta move3d project
See Also
createScene handles the creation of the project
void move3d::SceneManager::setScePath ( const std::string &  scePath)

set the path to a sce file to load on startup

Parameters
scePaththe path prefer absolute paths or ROS package:// url
void move3d::SceneManager::setUpdateAcceptBaseOnly ( bool  updateAcceptBaseOnly)

setUpdateAcceptBaseOnly

Parameters
updateAcceptBaseOnly
See Also
updateAcceptBaseOnly()
bool move3d::SceneManager::updateAcceptBaseOnly ( ) const

updateAcceptBaseOnly indicates the possibility to consider only the base position of an agent.

Returns

When True, calls to updateRobot with empty dof_values will result in the same as calling updateRobotPose. Otherwise the robot is not updated.

See Also
setUpdateAcceptBaseOnly()
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

Parameters
namename of the human in ROS
base_poseposition of the base joint of the human
jointsother joint positions (not configuration) in an absolute frame
Returns
false if the human is not found in the HumanMgr settings or in the move3d scene, or if the configuration cannot be computed
See Also
HumanMgr
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).

Parameters
namename of the robot to place
base_posethe base pose (pose of the 1st joint)
dof_valuesvalues of the other degrees of freedom (ordered as in ROS)
Returns
false on error
bool move3d::SceneManager::updateRobotM3d ( const std::string &  name,
std::vector< double > &  dof_values 
)

update a robot configuration (any moveable object).

Parameters
namename of the robot to place
dof_valuesvalue of all the degrees of freedom (ordered as in move3d)
Returns
The position of the 1st joint is specified as the first 6 DoFs of the vector: (x,y,z,rx,ry,rz)
bool move3d::SceneManager::updateRobotPose ( const std::string &  name,
const geometry_msgs::Pose &  base_pose 
)

update the base pose of a robot (any moveable obect).

Parameters
namename of the robot/object
base_posethe pose where to place the robot
Returns
false on error (robot does not exist,...)

The documentation for this class was generated from the following files: