move3d_ros_lib  0.1.0
move3d/ros API interface
 All Classes Namespaces Functions Variables Typedefs Pages
scenemanager.h
1 #ifndef SCENEMANAGER_H
2 #define SCENEMANAGER_H
3 
4 #include <string>
5 #include <set>
6 #include <vector>
7 #include <Eigen/Geometry>
8 #include <ros/ros.h>
9 #include <geometry_msgs/Pose.h>
10 
16 class Project;
17 namespace move3d
18 {
19 class HumanMgr;
20 
26 {
27 public:
32  SceneManager(ros::NodeHandle *nh);
38  SceneManager(ros::NodeHandle *nh,const std::string &p3d_path);
39 
40  ~SceneManager();
41 
50  bool addModule(const std::string &name);
51 
61  bool createScene();
62 
69  bool updateRobotPose(const std::string &name, const geometry_msgs::Pose &base_pose);
77  bool updateRobot(const std::string &name, const geometry_msgs::Pose &base_pose, const std::vector<double> &dof_values);
86  bool updateRobotM3d(const std::string &name, std::vector<double> &dof_values);
88  bool updateObject(const std::string &name, const geometry_msgs::Pose &pose);
89 
98  bool updateHuman(const std::string &name, const geometry_msgs::Pose &base_pose, const std::map<std::string,geometry_msgs::Pose> &joints);
99 
105  void setDofCorresp(const std::string &robot_name, const std::map<std::string,std::string> &ros_to_move3d_map);
114  bool setDofNameOrdered(const std::string &robot_name,const std::vector<std::string> &dof_names);
115 
145  bool fetchDofCorrespParam(const std::string &param_name, const std::string &robot_name);
155  bool fetchDofCorrespParam(const std::string &base_param_name);
156 
165  bool convertConfRosToM3d(const std::string &robot_name, const std::vector<double> &ros_conf, std::vector<double> &m3d_conf);
166 
171  std::string p3dPath() const;
177  void setP3dPath(const std::string &p3dPath);
178 
180  std::string scePath() const;
186  void setScePath(const std::string &scePath);
187 
194  bool saveScenario(const std::string &path);
195 
196 
198  Eigen::Affine3d getFrameTransform() const;
200  void setFrameTransform(const Eigen::Affine3d &frame_change);
201 
210  bool updateAcceptBaseOnly() const;
216  void setUpdateAcceptBaseOnly(bool updateAcceptBaseOnly);
217 
218  //getter / setters
219 
224  Project *project() const;
230  void setProject(Project *project);
231 
233  ros::NodeHandle *nh() const;
235  void setNh(ros::NodeHandle *nh);
236 
237  typedef std::map<std::string,std::string> NameMap_t;
238  typedef std::map<uint,uint> UintMap_t;
239  typedef std::map<std::string,NameMap_t> JointCorrespName_t;
240  typedef std::map<std::string,UintMap_t> JointCorrespIndex_t;
241 
242 
243 private:
245  void preInit();
246  ros::NodeHandle *_nh;
247  std::string _p3dPath;
248  std::string _scePath;
249 
250  std::set<std::string> _modules_to_activ;
251 
252  Project *_project;
253 
254  JointCorrespName_t _jointCorrespNames;
255  JointCorrespIndex_t _jointCorrespIndex;
256 
257  HumanMgr *_humanMgr;
258 
259  Eigen::Affine3d _frame_transform;
260 
261  bool _updateAcceptBaseOnly;
262 
263 };
264 
265 }
266 #endif // SCENEMANAGER_H
void setFrameTransform(const Eigen::Affine3d &frame_change)
Definition: scenemanager.cpp:381
bool createScene()
create the move3d scene and project.
Definition: scenemanager.cpp:87
void setNh(ros::NodeHandle *nh)
set the node handle
Definition: scenemanager.cpp:361
Eigen::Affine3d getFrameTransform() const
Definition: scenemanager.cpp:376
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.
Definition: scenemanager.h:25
bool updateAcceptBaseOnly() const
updateAcceptBaseOnly indicates the possibility to consider only the base position of an agent...
Definition: scenemanager.cpp:366
std::string p3dPath() const
get the path to the p3d file.
Definition: scenemanager.cpp:386
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.
Definition: scenemanager.cpp:336
void setP3dPath(const std::string &p3dPath)
set the path to the p3d file used to describe the environment and its robots and objects.
Definition: scenemanager.cpp:391
bool saveScenario(const std::string &path)
save the scenario, ie. the positions and configurations of all objects and robots ...
Definition: scenemanager.cpp:398
void setUpdateAcceptBaseOnly(bool updateAcceptBaseOnly)
setUpdateAcceptBaseOnly
Definition: scenemanager.cpp:371
std::string scePath() const
Definition: scenemanager.cpp:346
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.
Definition: scenemanager.cpp:226
bool updateRobotPose(const std::string &name, const geometry_msgs::Pose &base_pose)
update the base pose of a robot (any moveable obect).
Definition: scenemanager.cpp:125
SceneManager(ros::NodeHandle *nh)
default constructor
Definition: scenemanager.cpp:58
Project * project() const
get the move3d project object
Definition: scenemanager.cpp:411
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 e...
Definition: scenemanager.cpp:308
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).
Definition: scenemanager.cpp:149
void setProject(Project *project)
set a project instead of creating it with createScene
Definition: scenemanager.cpp:416
void setScePath(const std::string &scePath)
set the path to a sce file to load on startup
Definition: scenemanager.cpp:351
bool updateObject(const std::string &name, const geometry_msgs::Pose &pose)
as updateRobotPose(string,Pose)
Definition: scenemanager.cpp:208
bool updateHuman(const std::string &name, const geometry_msgs::Pose &base_pose, const std::map< std::string, geometry_msgs::Pose > &joints)
updatea human position
Definition: scenemanager.cpp:213
bool updateRobotM3d(const std::string &name, std::vector< double > &dof_values)
update a robot configuration (any moveable object).
Definition: scenemanager.cpp:179
ros::NodeHandle * nh() const
get the node handle
Definition: scenemanager.cpp:356
bool fetchDofCorrespParam(const std::string &param_name, const std::string &robot_name)
retrieve map of joint/dof correspondances
Definition: scenemanager.cpp:267
bool addModule(const std::string &name)
add a move3d module to be initialized
Definition: scenemanager.cpp:76
The HumanMgr class updates human configuration based on plugins.
Definition: humanmgr.h:37