|
XBotInterface
2.4.1
XBotInterface provides a generic API to model and control a robot.
|
#include <XBotCoreModel.h>
Inheritance diagram for XBot::XBotCoreModel:
Collaboration diagram for XBot::XBotCoreModel:Public Member Functions | |
| XBotCoreModel (void) | |
| urdf::ModelInterfaceSharedPtr | get_urdf_model (void) const |
| getter for the URDF ModelInterface More... | |
| KDL::Tree | get_robot_tree (void) |
| getter for the KDL robot tree More... | |
| const std::vector< std::string > & | get_chain_names (void) const |
| getter for the chain names vector More... | |
| const std::vector< std::string > & | get_ordered_chain_names (void) const |
| getter for the alphabetically ordered chain names vector More... | |
| bool | init (const std::string &urdf_filename, const std::string &srdf_filename, const std::string &joint_map_config) |
| initialization function for the model: it loads the URDF and parses the SRDF More... | |
| bool | init_from_string (const std::string &urdf, const std::string &srdf, const std::string &joint_map_config) |
| initialization function for the model: it loads the URDF and parses the SRDF More... | |
| bool | init (const std::string &urdf_filename, const std::string &srdf_filename) |
| initialization function for the model: it loads the URDF and parses the SRDF More... | |
| void | generate_robot (void) |
| dynamically generate the robot as a map {chain_name} -> {vector of enabled joints} More... | |
| virtual std::map< std::string, std::vector< int > > | get_robot (void) final |
| virtual std::map< std::string, int > | get_ft_sensors (void) final |
| virtual std::map< std::string, int > | get_imu_sensors () final |
| virtual std::map< std::string, int > | get_hands () final |
| virtual std::string | rid2Joint (int rId) final |
| virtual int | joint2Rid (std::string joint_name) final |
| bool | get_enabled_joints_in_chain (std::string chain_name, std::vector< std::string > &enabled_joints) const |
| getter for the enabled joints vector in the chain More... | |
| bool | get_disabled_joints_in_chain (std::string chain_name, std::vector< std::string > &disabled_joints) const |
| getter for the disabled joints vector in the chain More... | |
| void | get_enabled_joint_names (std::vector< std::string > &joint_names) const |
| get the vector of the enabled joint names of the whole robot More... | |
| void | get_enabled_joint_ids (std::vector< int > &joint_ids) const |
| get the vector of the enabled joint ids of the whole robot More... | |
| bool | get_enabled_joint_ids_in_chain (std::string chain_name, std::vector< int > &joint_ids) const |
| get the vector of the joint ids of the requested chain More... | |
| int | get_joint_num () const |
| get the number of joint in the robot More... | |
| int | get_joint_num (std::string chain_name) const |
| get the number of joint of a requested chain More... | |
| const std::string & | get_urdf_string () const |
| Get the robot URDF as a string. More... | |
| const std::string & | get_srdf_string () const |
| Get the robot SRDF as a string. More... | |
| const std::vector< std::string > & | get_legs_chain () const |
| Get the legs chain names ordered as in the SRDF. More... | |
| const std::vector< std::string > & | get_arms_chain () const |
| Get the arms chain names ordered as in the SRDF. More... | |
| bool | check_joint_limits () const |
| ~XBotCoreModel () | |
Public Member Functions inherited from XBot::IXBotModel | |
| virtual | ~IXBotModel () |
|
inline |
|
inline |
| bool XBot::XBotCoreModel::check_joint_limits | ( | ) | const |
| void XBot::XBotCoreModel::generate_robot | ( | void | ) |
dynamically generate the robot as a map {chain_name} -> {vector of enabled joints}
| ... |
| const std::vector< std::string > & XBot::XBotCoreModel::get_arms_chain | ( | ) | const |
Get the arms chain names ordered as in the SRDF.
|
inline |
getter for the chain names vector
| bool XBot::XBotCoreModel::get_disabled_joints_in_chain | ( | std::string | chain_name, |
| std::vector< std::string > & | disabled_joints | ||
| ) | const |
getter for the disabled joints vector in the chain
| chain_name | the requested chain name |
| disabled_joints | vector that will be filled with the disabled joint names |
| void XBot::XBotCoreModel::get_enabled_joint_ids | ( | std::vector< int > & | joint_ids | ) | const |
get the vector of the enabled joint ids of the whole robot
| joint_names | array of the joint ids filled by this function |
| bool XBot::XBotCoreModel::get_enabled_joint_ids_in_chain | ( | std::string | chain_name, |
| std::vector< int > & | joint_ids | ||
| ) | const |
get the vector of the joint ids of the requested chain
| chain_name | the requested chain |
| joint_names | array of the joint ids of the requested chain filled by this function |
| void XBot::XBotCoreModel::get_enabled_joint_names | ( | std::vector< std::string > & | joint_names | ) | const |
get the vector of the enabled joint names of the whole robot
| joint_names | array of the joint names filled by this function |
| bool XBot::XBotCoreModel::get_enabled_joints_in_chain | ( | std::string | chain_name, |
| std::vector< std::string > & | enabled_joints | ||
| ) | const |
getter for the enabled joints vector in the chain
| chain_name | the requested chain name |
| enabled_joints | vector that will be filled with the enabled joint names |
|
inlinefinalvirtual |
Implements XBot::IXBotModel.
|
inlinefinalvirtual |
Implements XBot::IXBotModel.
|
inlinefinalvirtual |
Implements XBot::IXBotModel.
| int XBot::XBotCoreModel::get_joint_num | ( | ) | const |
get the number of joint in the robot
| int XBot::XBotCoreModel::get_joint_num | ( | std::string | chain_name | ) | const |
get the number of joint of a requested chain
| chain_name | the requested chain |
| const std::vector< std::string > & XBot::XBotCoreModel::get_legs_chain | ( | ) | const |
Get the legs chain names ordered as in the SRDF.
|
inline |
getter for the alphabetically ordered chain names vector
|
inlinefinalvirtual |
Implements XBot::IXBotModel.
|
inline |
getter for the KDL robot tree
| const std::string & XBot::XBotCoreModel::get_srdf_string | ( | ) | const |
Get the robot SRDF as a string.
|
inline |
getter for the URDF ModelInterface
| const std::string & XBot::XBotCoreModel::get_urdf_string | ( | ) | const |
Get the robot URDF as a string.
| bool XBot::XBotCoreModel::init | ( | const std::string & | urdf_filename, |
| const std::string & | srdf_filename | ||
| ) |
initialization function for the model: it loads the URDF and parses the SRDF
| urdf_filename | URDF path |
| srdf_filename | SRDF path |
| bool XBot::XBotCoreModel::init | ( | const std::string & | urdf_filename, |
| const std::string & | srdf_filename, | ||
| const std::string & | joint_map_config | ||
| ) |
initialization function for the model: it loads the URDF and parses the SRDF
| urdf_filename | URDF path |
| srdf_filename | SRDF path |
| joint_map_config | joint_map_config path |
| bool XBot::XBotCoreModel::init_from_string | ( | const std::string & | urdf, |
| const std::string & | srdf, | ||
| const std::string & | joint_map_config | ||
| ) |
initialization function for the model: it loads the URDF and parses the SRDF
| urdf | URDF as string |
| srdf | SRDF as string |
| joint_map_config | joint ID map as string |
|
inlinefinalvirtual |
Implements XBot::IXBotModel.
|
inlinefinalvirtual |
Implements XBot::IXBotModel.
1.8.17