A joint from the robot. Contains the transform applied by the joint type. More...
#include <kinematic_model.h>
Public Types | |
typedef boost::bimap < std::string, std::string > | js_type |
Public Member Functions | |
virtual std::vector< double > | computeJointStateValues (const btTransform &transform) const =0 |
virtual btTransform | computeTransform (const std::vector< double > &joint_values) const =0 |
const std::map< std::string, std::pair< double, double > > & | getAllVariableBounds () const |
const std::string & | getChildFrameId () const |
const LinkModel * | getChildLinkModel () const |
const std::map< unsigned int, std::string > & | getComputatationOrderMapIndex () const |
std::string | getEquiv (const std::string name) const |
Gets the joint state equivalent for given name. | |
const js_type & | getJointStateEquivalents () const |
const std::string & | getName () const |
const std::string & | getParentFrameId () const |
const LinkModel * | getParentLinkModel () const |
std::pair< double, double > | getVariableBounds (std::string variable) const |
Gets the lower and upper bounds for a variable. | |
bool | hasVariable (const std::string var) const |
void | initialize (const std::vector< std::string > &local_names, const MultiDofConfig *multi_dof_config=NULL) |
JointModel (const JointModel *joint) | |
JointModel (const std::string &name) | |
void | setVariableBounds (std::string variable, double low, double high) |
Sets the lower and upper bounds for a variable. | |
virtual | ~JointModel (void) |
Private Attributes | |
std::string | child_frame_id_ |
LinkModel * | child_link_model_ |
The link after this joint. | |
std::map< unsigned int, std::string > | computation_order_map_index_ |
std::map< std::string, std::pair< double, double > > | joint_state_bounds_ |
js_type | joint_state_equivalents_ |
std::string | name_ |
Name of the joint. | |
std::string | parent_frame_id_ |
LinkModel * | parent_link_model_ |
The link before this joint. | |
Friends | |
class | KinematicModel |
A joint from the robot. Contains the transform applied by the joint type.
Definition at line 80 of file kinematic_model.h.
typedef boost::bimap< std::string, std::string > planning_models::KinematicModel::JointModel::js_type |
Definition at line 93 of file kinematic_model.h.
planning_models::KinematicModel::JointModel::JointModel | ( | const std::string & | name | ) |
Definition at line 616 of file kinematic_model.cpp.
planning_models::KinematicModel::JointModel::JointModel | ( | const JointModel * | joint | ) |
Definition at line 655 of file kinematic_model.cpp.
planning_models::KinematicModel::JointModel::~JointModel | ( | void | ) | [virtual] |
Definition at line 663 of file kinematic_model.cpp.
virtual std::vector<double> planning_models::KinematicModel::JointModel::computeJointStateValues | ( | const btTransform & | transform | ) | const [pure virtual] |
virtual btTransform planning_models::KinematicModel::JointModel::computeTransform | ( | const std::vector< double > & | joint_values | ) | const [pure virtual] |
const std::map<std::string, std::pair<double, double> >& planning_models::KinematicModel::JointModel::getAllVariableBounds | ( | ) | const [inline] |
Definition at line 138 of file kinematic_model.h.
const std::string& planning_models::KinematicModel::JointModel::getChildFrameId | ( | ) | const [inline] |
Definition at line 115 of file kinematic_model.h.
const LinkModel* planning_models::KinematicModel::JointModel::getChildLinkModel | ( | ) | const [inline] |
Definition at line 105 of file kinematic_model.h.
const std::map<unsigned int, std::string>& planning_models::KinematicModel::JointModel::getComputatationOrderMapIndex | ( | ) | const [inline] |
Definition at line 125 of file kinematic_model.h.
std::string planning_models::KinematicModel::JointModel::getEquiv | ( | const std::string | name | ) | const |
Gets the joint state equivalent for given name.
Definition at line 669 of file kinematic_model.cpp.
const js_type& planning_models::KinematicModel::JointModel::getJointStateEquivalents | ( | ) | const [inline] |
Definition at line 120 of file kinematic_model.h.
const std::string& planning_models::KinematicModel::JointModel::getName | ( | ) | const [inline] |
Definition at line 95 of file kinematic_model.h.
const std::string& planning_models::KinematicModel::JointModel::getParentFrameId | ( | ) | const [inline] |
Definition at line 110 of file kinematic_model.h.
const LinkModel* planning_models::KinematicModel::JointModel::getParentLinkModel | ( | ) | const [inline] |
Definition at line 100 of file kinematic_model.h.
std::pair< double, double > planning_models::KinematicModel::JointModel::getVariableBounds | ( | std::string | variable | ) | const |
Gets the lower and upper bounds for a variable.
Definition at line 686 of file kinematic_model.cpp.
bool planning_models::KinematicModel::JointModel::hasVariable | ( | const std::string | var | ) | const [inline] |
Definition at line 142 of file kinematic_model.h.
void planning_models::KinematicModel::JointModel::initialize | ( | const std::vector< std::string > & | local_names, | |
const MultiDofConfig * | multi_dof_config = NULL | |||
) |
Definition at line 621 of file kinematic_model.cpp.
void planning_models::KinematicModel::JointModel::setVariableBounds | ( | std::string | variable, | |
double | low, | |||
double | high | |||
) |
Sets the lower and upper bounds for a variable.
Definition at line 678 of file kinematic_model.cpp.
friend class KinematicModel [friend] |
Definition at line 82 of file kinematic_model.h.
std::string planning_models::KinematicModel::JointModel::child_frame_id_ [private] |
The child frame id for this joint. May be empty unless specified as multi-dof
Definition at line 175 of file kinematic_model.h.
The link after this joint.
Definition at line 160 of file kinematic_model.h.
std::map<unsigned int, std::string> planning_models::KinematicModel::JointModel::computation_order_map_index_ [private] |
Definition at line 169 of file kinematic_model.h.
std::map<std::string, std::pair<double, double> > planning_models::KinematicModel::JointModel::joint_state_bounds_ [private] |
Definition at line 166 of file kinematic_model.h.
Definition at line 163 of file kinematic_model.h.
std::string planning_models::KinematicModel::JointModel::name_ [private] |
Name of the joint.
Definition at line 154 of file kinematic_model.h.
std::string planning_models::KinematicModel::JointModel::parent_frame_id_ [private] |
The parent frame id for this joint. May be empty unless specified as multi-dof
Definition at line 172 of file kinematic_model.h.
The link before this joint.
Definition at line 157 of file kinematic_model.h.