2 #ifndef INTERFACE_MAPPING_H_ 3 #define INTERFACE_MAPPING_H_ 7 #include <boost/bimap.hpp> 8 #include <boost/bimap/multiset_of.hpp> 9 #include <boost/foreach.hpp> 14 typedef boost::bimap<boost::bimaps::multiset_of<std::string>, boost::bimaps::set_of<canopen::MotorBase::OperationMode> >
bimap_type;
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);
37 bimap_type::right_const_iterator it;
38 if((it = mapping_.right.find(mode)) != mapping_.right.end()){
39 return it->second != interface;
boost::bimap< boost::bimaps::multiset_of< std::string >, boost::bimaps::set_of< canopen::MotorBase::OperationMode > > bimap_type
Cyclic_Synchronous_Position
std::vector< canopen::MotorBase::OperationMode > getInterfaceModes(const std::string &interface)
bool hasConflict(const std::string &interface, canopen::MotorBase::OperationMode mode)
Cyclic_Synchronous_Torque
Cyclic_Synchronous_Velocity
InterfaceMapping g_interface_mapping