Public Member Functions | Protected Member Functions | Protected Attributes
planning_environment::RobotModels Class Reference

A class capable of loading a robot model from the parameter server. More...

#include <robot_models.h>

Inheritance diagram for planning_environment::RobotModels:
Inheritance graph
[legend]

List of all members.

Public Member Functions

const std::string & getDescription (void) const
 Return the name of the description.
const
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::string & getRobotFrameId (void) const
 Return the frame id of the state.
std::string getRobotName (void) const
const std::string & getWorldFrameId (void) const
 Return the world frame id.
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)
 RobotModels (boost::shared_ptr< urdf::Model > urdf, planning_models::KinematicModel *kmodel)
virtual ~RobotModels (void)

Protected Member Functions

void loadGroupConfigsFromParamServer (const std::vector< planning_models::KinematicModel::MultiDofConfig > &multi_dof_configs, std::vector< planning_models::KinematicModel::GroupConfig > &configs)
bool loadMultiDofConfigsFromParamServer (std::vector< planning_models::KinematicModel::MultiDofConfig > &configs)
void loadRobotFromParamServer (void)

Protected Attributes

std::string description_
planning_models::KinematicModelkmodel_
bool loaded_models_
ros::NodeHandle nh_
ros::NodeHandle priv_nh_
boost::shared_ptr< urdf::Modelurdf_

Detailed Description

A class capable of loading a robot model from the parameter server.

Definition at line 53 of file robot_models.h.


Constructor & Destructor Documentation

planning_environment::RobotModels::RobotModels ( const std::string &  description)
Author:
Ioan Sucan

Definition at line 43 of file robot_models.cpp.

Definition at line 50 of file robot_models.cpp.

virtual planning_environment::RobotModels::~RobotModels ( void  ) [inline, virtual]

Definition at line 62 of file robot_models.h.


Member Function Documentation

const std::string& planning_environment::RobotModels::getDescription ( void  ) const [inline]

Return the name of the description.

Definition at line 68 of file robot_models.h.

Return the instance of the constructed kinematic model.

Definition at line 74 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 80 of file robot_models.h.

const std::string& planning_environment::RobotModels::getRobotFrameId ( void  ) const [inline]

Return the frame id of the state.

Definition at line 97 of file robot_models.h.

std::string planning_environment::RobotModels::getRobotName ( void  ) const [inline]

Definition at line 108 of file robot_models.h.

const std::string& planning_environment::RobotModels::getWorldFrameId ( void  ) const [inline]

Return the world frame id.

Definition at line 103 of file robot_models.h.

Return true if models have been loaded.

Definition at line 86 of file robot_models.h.

Definition at line 154 of file robot_models.cpp.

Definition at line 94 of file robot_models.cpp.

Definition at line 65 of file robot_models.cpp.

void planning_environment::RobotModels::reload ( void  ) [virtual]

Reload the robot description and recreate the model.

Definition at line 58 of file robot_models.cpp.


Member Data Documentation

Definition at line 124 of file robot_models.h.

Definition at line 127 of file robot_models.h.

Definition at line 126 of file robot_models.h.

Definition at line 121 of file robot_models.h.

Definition at line 122 of file robot_models.h.

boost::shared_ptr<urdf::Model> planning_environment::RobotModels::urdf_ [protected]

Definition at line 129 of file robot_models.h.


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


planning_environment
Author(s): Ioan Sucan
autogenerated on Thu Dec 12 2013 11:09:24