A class capable of loading a robot model from the parameter server. More...
#include <robot_models.h>
Classes | |
struct | GroupConfig |
Public Member Functions | |
const std::string & | getDescription (void) const |
Return the name of the description. | |
const std::vector< std::string > & | getGroupJointUnion (void) const |
Gets the union of all the joints in all planning groups. | |
const std::vector< std::string > & | getGroupLinkUnion (void) const |
Gets the union of all the links in all planning groups. | |
const boost::shared_ptr < planning_models::KinematicModel > & | getKinematicModel (void) const |
Return the instance of the constructed kinematic model. | |
const boost::shared_ptr < urdf::Model > & | getParsedDescription (void) const |
Return the instance of the parsed robot description. | |
const std::map< std::string, std::vector< std::string > > & | getPlanningGroupJoints (void) const |
Return the map of the planning group joints. | |
const std::map< std::string, std::vector< std::string > > & | getPlanningGroupLinks (void) const |
Return the map of the planning group links. | |
bool | loadedModels (void) const |
Return true if models have been loaded. | |
virtual void | reload (void) |
Reload the robot description and recreate the model. | |
RobotModels (const std::string &description) | |
virtual | ~RobotModels (void) |
Protected Member Functions | |
void | loadRobot (void) |
void | readGroupConfigs () |
bool | readMultiDofConfigs () |
Protected Attributes | |
std::string | description_ |
std::map< std::string, GroupConfig * > | group_config_map_ |
std::vector< std::string > | group_joint_union_ |
std::vector< std::string > | group_link_union_ |
boost::shared_ptr < planning_models::KinematicModel > | kmodel_ |
bool | loaded_models_ |
std::vector < planning_models::KinematicModel::MultiDofConfig > | multi_dof_configs_ |
ros::NodeHandle | nh_ |
std::map< std::string, std::vector< std::string > > | planning_group_joints_ |
std::map< std::string, std::vector< std::string > > | planning_group_links_ |
boost::shared_ptr< urdf::Model > | urdf_ |
A class capable of loading a robot model from the parameter server.
Definition at line 53 of file robot_models.h.
planning_environment::RobotModels::RobotModels | ( | const std::string & | description | ) | [inline] |
Definition at line 77 of file robot_models.h.
virtual planning_environment::RobotModels::~RobotModels | ( | void | ) | [inline, virtual] |
Definition at line 84 of file robot_models.h.
const std::string& planning_environment::RobotModels::getDescription | ( | void | ) | const [inline] |
Return the name of the description.
Definition at line 94 of file robot_models.h.
const std::vector<std::string>& planning_environment::RobotModels::getGroupJointUnion | ( | void | ) | const [inline] |
Gets the union of all the joints in all planning groups.
Definition at line 123 of file robot_models.h.
const std::vector<std::string>& planning_environment::RobotModels::getGroupLinkUnion | ( | void | ) | const [inline] |
Gets the union of all the links in all planning groups.
Definition at line 128 of file robot_models.h.
const boost::shared_ptr<planning_models::KinematicModel>& planning_environment::RobotModels::getKinematicModel | ( | void | ) | const [inline] |
Return the instance of the constructed kinematic model.
Definition at line 100 of file robot_models.h.
const boost::shared_ptr<urdf::Model>& planning_environment::RobotModels::getParsedDescription | ( | void | ) | const [inline] |
Return the instance of the parsed robot description.
Definition at line 106 of file robot_models.h.
const std::map< std::string, std::vector<std::string> >& planning_environment::RobotModels::getPlanningGroupJoints | ( | void | ) | const [inline] |
Return the map of the planning group joints.
Definition at line 112 of file robot_models.h.
const std::map<std::string, std::vector<std::string> >& planning_environment::RobotModels::getPlanningGroupLinks | ( | void | ) | const [inline] |
Return the map of the planning group links.
Definition at line 118 of file robot_models.h.
bool planning_environment::RobotModels::loadedModels | ( | void | ) | const [inline] |
Return true if models have been loaded.
Definition at line 133 of file robot_models.h.
void planning_environment::RobotModels::loadRobot | ( | void | ) | [protected] |
Definition at line 61 of file robot_models.cpp.
void planning_environment::RobotModels::readGroupConfigs | ( | ) | [protected] |
Definition at line 146 of file robot_models.cpp.
bool planning_environment::RobotModels::readMultiDofConfigs | ( | ) | [protected] |
Definition at line 88 of file robot_models.cpp.
void planning_environment::RobotModels::reload | ( | void | ) | [virtual] |
Reload the robot description and recreate the model.
Reimplemented in planning_environment::CollisionModels.
Definition at line 43 of file robot_models.cpp.
std::string planning_environment::RobotModels::description_ [protected] |
Definition at line 151 of file robot_models.h.
std::map< std::string, GroupConfig*> planning_environment::RobotModels::group_config_map_ [protected] |
Definition at line 162 of file robot_models.h.
std::vector<std::string> planning_environment::RobotModels::group_joint_union_ [protected] |
Definition at line 160 of file robot_models.h.
std::vector<std::string> planning_environment::RobotModels::group_link_union_ [protected] |
Definition at line 161 of file robot_models.h.
boost::shared_ptr<planning_models::KinematicModel> planning_environment::RobotModels::kmodel_ [protected] |
Definition at line 154 of file robot_models.h.
bool planning_environment::RobotModels::loaded_models_ [protected] |
Definition at line 153 of file robot_models.h.
std::vector<planning_models::KinematicModel::MultiDofConfig> planning_environment::RobotModels::multi_dof_configs_ [protected] |
Definition at line 163 of file robot_models.h.
ros::NodeHandle planning_environment::RobotModels::nh_ [protected] |
Definition at line 149 of file robot_models.h.
std::map< std::string, std::vector<std::string> > planning_environment::RobotModels::planning_group_joints_ [protected] |
Definition at line 159 of file robot_models.h.
std::map< std::string, std::vector<std::string> > planning_environment::RobotModels::planning_group_links_ [protected] |
Definition at line 158 of file robot_models.h.
boost::shared_ptr<urdf::Model> planning_environment::RobotModels::urdf_ [protected] |
Definition at line 156 of file robot_models.h.