interface_mapping.h
Go to the documentation of this file.
1 
2 #ifndef INTERFACE_MAPPING_H_
3 #define INTERFACE_MAPPING_H_
4 
5 #include <string>
6 
7 #include <boost/bimap.hpp>
8 #include <boost/bimap/multiset_of.hpp>
9 #include <boost/foreach.hpp>
10 
11 #include <canopen_402/base.h>
12 
14  typedef boost::bimap<boost::bimaps::multiset_of<std::string>, boost::bimaps::set_of<canopen::MotorBase::OperationMode> > bimap_type;
15  bimap_type mapping_;
16 public:
18  mapping_.insert(bimap_type::value_type("hardware_interface::PositionJointInterface" ,canopen::MotorBase::Profiled_Position));
19  mapping_.insert(bimap_type::value_type("hardware_interface::PositionJointInterface" ,canopen::MotorBase::Interpolated_Position));
20  mapping_.insert(bimap_type::value_type("hardware_interface::PositionJointInterface" ,canopen::MotorBase::Cyclic_Synchronous_Position));
21 
22  mapping_.insert(bimap_type::value_type("hardware_interface::VelocityJointInterface" ,canopen::MotorBase::Velocity));
23  mapping_.insert(bimap_type::value_type("hardware_interface::VelocityJointInterface" ,canopen::MotorBase::Profiled_Velocity));
24  mapping_.insert(bimap_type::value_type("hardware_interface::VelocityJointInterface" ,canopen::MotorBase::Cyclic_Synchronous_Velocity));
25 
26  mapping_.insert(bimap_type::value_type("hardware_interface::EffortJointInterface" ,canopen::MotorBase::Profiled_Torque));
27  mapping_.insert(bimap_type::value_type("hardware_interface::EffortJointInterface" ,canopen::MotorBase::Cyclic_Synchronous_Torque));
28  }
29  std::vector<canopen::MotorBase::OperationMode> getInterfaceModes(const std::string &interface){
30  std::vector<canopen::MotorBase::OperationMode> modes;
31  BOOST_FOREACH(bimap_type::left_reference i, mapping_.left.equal_range(interface)){
32  modes.push_back(i.second);
33  }
34  return modes;
35  }
36  bool hasConflict(const std::string &interface, canopen::MotorBase::OperationMode mode){
37  bimap_type::right_const_iterator it;
38  if((it = mapping_.right.find(mode)) != mapping_.right.end()){
39  return it->second != interface;
40  }
41  return false;
42  }
43 
44 };
45 
47 
48 #endif /* INTERFACE_MAPPING_H_ */
boost::bimap< boost::bimaps::multiset_of< std::string >, boost::bimaps::set_of< canopen::MotorBase::OperationMode > > bimap_type
std::vector< canopen::MotorBase::OperationMode > getInterfaceModes(const std::string &interface)
bool hasConflict(const std::string &interface, canopen::MotorBase::OperationMode mode)
InterfaceMapping g_interface_mapping
Definition: robot_layer.cpp:16


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sat May 4 2019 02:40:47