XBotInterface  2.4.1
XBotInterface provides a generic API to model and control a robot.
Public Member Functions | List of all members
XBot::XBotCoreModel Class Reference

#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 ()
 

Constructor & Destructor Documentation

◆ XBotCoreModel()

XBot::XBotCoreModel::XBotCoreModel ( void  )
inline

◆ ~XBotCoreModel()

XBot::XBotCoreModel::~XBotCoreModel ( )
inline

Member Function Documentation

◆ check_joint_limits()

bool XBot::XBotCoreModel::check_joint_limits ( ) const

◆ generate_robot()

void XBot::XBotCoreModel::generate_robot ( void  )

dynamically generate the robot as a map {chain_name} -> {vector of enabled joints}

Parameters
...
Returns
void

◆ get_arms_chain()

const std::vector< std::string > & XBot::XBotCoreModel::get_arms_chain ( ) const

Get the arms chain names ordered as in the SRDF.

Returns
the arms chain names ordered as in the SRDF

◆ get_chain_names()

const std::vector<std::string>& XBot::XBotCoreModel::get_chain_names ( void  ) const
inline

getter for the chain names vector

Returns
std::vector< std::::string> the chain names vector

◆ get_disabled_joints_in_chain()

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

Parameters
chain_namethe requested chain name
disabled_jointsvector that will be filled with the disabled joint names
Returns
bool true if the chain exists, false otherwise

◆ get_enabled_joint_ids()

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

Parameters
joint_namesarray of the joint ids filled by this function
Returns
void

◆ get_enabled_joint_ids_in_chain()

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

Parameters
chain_namethe requested chain
joint_namesarray of the joint ids of the requested chain filled by this function
Returns
void

◆ get_enabled_joint_names()

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

Parameters
joint_namesarray of the joint names filled by this function
Returns
void

◆ get_enabled_joints_in_chain()

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

Parameters
chain_namethe requested chain name
enabled_jointsvector that will be filled with the enabled joint names
Returns
bool true if the chain exists, false otherwise

◆ get_ft_sensors()

virtual std::map<std::string,int> XBot::XBotCoreModel::get_ft_sensors ( void  )
inlinefinalvirtual

Implements XBot::IXBotModel.

◆ get_hands()

virtual std::map<std::string, int> XBot::XBotCoreModel::get_hands ( )
inlinefinalvirtual

Implements XBot::IXBotModel.

◆ get_imu_sensors()

virtual std::map<std::string, int> XBot::XBotCoreModel::get_imu_sensors ( )
inlinefinalvirtual

Implements XBot::IXBotModel.

◆ get_joint_num() [1/2]

int XBot::XBotCoreModel::get_joint_num ( ) const

get the number of joint in the robot

Returns
the number of joint of the robot

◆ get_joint_num() [2/2]

int XBot::XBotCoreModel::get_joint_num ( std::string  chain_name) const

get the number of joint of a requested chain

Parameters
chain_namethe requested chain
Returns
the number of joint of the requested chain

◆ get_legs_chain()

const std::vector< std::string > & XBot::XBotCoreModel::get_legs_chain ( ) const

Get the legs chain names ordered as in the SRDF.

Returns
the legs chain names ordered as in the SRDF

◆ get_ordered_chain_names()

const std::vector<std::string>& XBot::XBotCoreModel::get_ordered_chain_names ( void  ) const
inline

getter for the alphabetically ordered chain names vector

Returns
std::vector< std::::string> the chain names vector

◆ get_robot()

virtual std::map<std::string, std::vector<int> > XBot::XBotCoreModel::get_robot ( void  )
inlinefinalvirtual

Implements XBot::IXBotModel.

◆ get_robot_tree()

KDL::Tree XBot::XBotCoreModel::get_robot_tree ( void  )
inline

getter for the KDL robot tree

Returns
KDL::Tree the KDL robot tree

◆ get_srdf_string()

const std::string & XBot::XBotCoreModel::get_srdf_string ( ) const

Get the robot SRDF as a string.

Returns
SRDF file as a const std::string&

◆ get_urdf_model()

urdf::ModelInterfaceSharedPtr XBot::XBotCoreModel::get_urdf_model ( void  ) const
inline

getter for the URDF ModelInterface

Returns
std::shared_ptr< urdf::ModelInterface > the URDF ModelInterface

◆ get_urdf_string()

const std::string & XBot::XBotCoreModel::get_urdf_string ( ) const

Get the robot URDF as a string.

Returns
URDF file as a const std::string&

◆ init() [1/2]

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

Parameters
urdf_filenameURDF path
srdf_filenameSRDF path
Returns
bool true on success, false otherwise

◆ init() [2/2]

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

Parameters
urdf_filenameURDF path
srdf_filenameSRDF path
joint_map_configjoint_map_config path
Returns
bool true on success, false otherwise

◆ init_from_string()

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

Parameters
urdfURDF as string
srdfSRDF as string
joint_map_configjoint ID map as string
Returns
bool true on success, false otherwise

◆ joint2Rid()

virtual int XBot::XBotCoreModel::joint2Rid ( std::string  joint_name)
inlinefinalvirtual

Implements XBot::IXBotModel.

◆ rid2Joint()

virtual std::string XBot::XBotCoreModel::rid2Joint ( int  rId)
inlinefinalvirtual

Implements XBot::IXBotModel.


The documentation for this class was generated from the following files: