interface_mapping.h
Go to the documentation of this file.
00001 
00002 #ifndef INTERFACE_MAPPING_H_
00003 #define INTERFACE_MAPPING_H_
00004 
00005 #include <string>
00006 
00007 #include <boost/bimap.hpp>
00008 #include <boost/bimap/multiset_of.hpp>
00009 #include <boost/foreach.hpp>
00010 
00011 #include <canopen_402/base.h>
00012 
00013 class InterfaceMapping {
00014     typedef boost::bimap<boost::bimaps::multiset_of<std::string>, boost::bimaps::set_of<canopen::MotorBase::OperationMode>  > bimap_type;
00015     bimap_type mapping_;
00016 public:
00017     InterfaceMapping(){
00018         mapping_.insert(bimap_type::value_type("hardware_interface::PositionJointInterface" ,canopen::MotorBase::Profiled_Position));
00019         mapping_.insert(bimap_type::value_type("hardware_interface::PositionJointInterface" ,canopen::MotorBase::Interpolated_Position));
00020         mapping_.insert(bimap_type::value_type("hardware_interface::PositionJointInterface" ,canopen::MotorBase::Cyclic_Synchronous_Position));
00021 
00022         mapping_.insert(bimap_type::value_type("hardware_interface::VelocityJointInterface" ,canopen::MotorBase::Velocity));
00023         mapping_.insert(bimap_type::value_type("hardware_interface::VelocityJointInterface" ,canopen::MotorBase::Profiled_Velocity));
00024         mapping_.insert(bimap_type::value_type("hardware_interface::VelocityJointInterface" ,canopen::MotorBase::Cyclic_Synchronous_Velocity));
00025 
00026         mapping_.insert(bimap_type::value_type("hardware_interface::EffortJointInterface" ,canopen::MotorBase::Profiled_Torque));
00027         mapping_.insert(bimap_type::value_type("hardware_interface::EffortJointInterface" ,canopen::MotorBase::Cyclic_Synchronous_Torque));
00028     }
00029     std::vector<canopen::MotorBase::OperationMode> getInterfaceModes(const std::string &interface){
00030         std::vector<canopen::MotorBase::OperationMode> modes;
00031         BOOST_FOREACH(bimap_type::left_reference i, mapping_.left.equal_range(interface)){
00032             modes.push_back(i.second);
00033         }
00034         return modes;
00035     }
00036     bool hasConflict(const std::string &interface, canopen::MotorBase::OperationMode mode){
00037         bimap_type::right_const_iterator it;
00038         if((it = mapping_.right.find(mode)) != mapping_.right.end()){
00039             return it->second != interface;
00040         }
00041         return false;
00042     }
00043   
00044 };
00045 
00046 extern InterfaceMapping g_interface_mapping;
00047 
00048 #endif /* INTERFACE_MAPPING_H_ */


canopen_motor_node
Author(s): Mathias Lüdtke
autogenerated on Sun Sep 3 2017 03:10:55