move3d_ros_lib  0.1.0
move3d/ros API interface
 All Classes Namespaces Functions Variables Typedefs Pages
base_human_updater.h
1 #ifndef BASEHUMANUPDATER_H
2 #define BASEHUMANUPDATER_H
3 
4 #include <boost/shared_ptr.hpp>
5 #include <Eigen/Geometry>
6 
7 #include <vector>
8 #include <string>
9 #include <map>
10 
11 class Robot;
12 class RobotState;
13 
14 namespace move3d
15 {
16 class BaseHumanUpdater;
23  HumanSettings(const std::map<std::string, float> &settings, const std::string &policy, const std::string &move3d_name)
24  {
25  this->policy=policy;
26  data=settings;
27  this->move3d_name=move3d_name;
28  }
30  bool getData(std::string key,float &v) const{
31  std::map<std::string,float>::const_iterator it=data.find(key);
32  if(it!=data.end()){
33  v=it->second;
34  return true;
35  }
36  return false;
37  }
39  std::string policy;
41  boost::shared_ptr<BaseHumanUpdater> updater;
43  std::map<std::string,float> data;
45  std::string move3d_name;
46 
47 };
48 typedef boost::shared_ptr<HumanSettings> HumanSettingsPtr;
49 
58 {
59 public:
60  virtual ~BaseHumanUpdater(){}
61 
70  virtual bool update(Robot *h,const Eigen::Affine3d &base,const std::map<std::string,Eigen::Affine3d> &joints,const HumanSettings &settings)=0;
80  virtual bool computeConf(Robot *h,const Eigen::Affine3d &base,const std::map<std::string,Eigen::Affine3d> &joints,const HumanSettings &settings, RobotState &q)=0;
81 
82 protected:
84 
85 };
86 
87 
88 
89 }
90 
91 #endif
virtual bool computeConf(Robot *h, const Eigen::Affine3d &base, const std::map< std::string, Eigen::Affine3d > &joints, const HumanSettings &settings, RobotState &q)=0
compute the configuration without updating the human in move3d
boost::shared_ptr< HumanSettings > HumanSettingsPtr
HumanSettingsPtr.
Definition: humanmgr.h:21
virtual bool update(Robot *h, const Eigen::Affine3d &base, const std::map< std::string, Eigen::Affine3d > &joints, const HumanSettings &settings)=0
update the robot with the given elements
std::string policy
name of the plugin to use
Definition: base_human_updater.h:39
bool getData(std::string key, float &v) const
handler to access to the data in the data map
Definition: base_human_updater.h:30
The HumanSettings struct stores data for each human.
Definition: base_human_updater.h:19
HumanSettings()
default constructor
Definition: base_human_updater.h:21
boost::shared_ptr< BaseHumanUpdater > updater
pointer to the updater object (plugin)
Definition: base_human_updater.h:41
Definition: base_human_updater.h:57
std::string move3d_name
name of the human in move3d (i.e. in the p3d file)
Definition: base_human_updater.h:45
HumanSettings(const std::map< std::string, float > &settings, const std::string &policy, const std::string &move3d_name)
constructor
Definition: base_human_updater.h:23
std::map< std::string, float > data
specific data passed to the updater
Definition: base_human_updater.h:43