A joint from the robot. Models the transform that this joint applies in the kinematic chain. A joint consists of multiple variables. In the simplest case, when the joint is a single DOF, there is only one variable and its name is the same as the joint's name. For multi-DOF joints, each variable has a local name (e.g., x, y) but the full variable name as seen from the outside of this class is a concatenation of the "joint name"/"local name" (e.g., a joint named 'base' with local variables 'x' and 'y' will store its full variable names as 'base/x' and 'base/y'). Local names are never used to reference variables directly. More...
#include <joint_model.h>
Public Types | |
typedef std::vector< std::pair < double, double > > | Bounds |
The datatype for the joint bounds. | |
enum | JointType { UNKNOWN, REVOLUTE, PRISMATIC, PLANAR, FLOATING, FIXED } |
The different types of joints we support. More... | |
Public Member Functions | |
virtual double | distance (const std::vector< double > &values1, const std::vector< double > &values2) const =0 |
Compute the distance between two joint states of the same model (represented by the variable values) | |
const LinkModel * | getChildLinkModel () const |
Get the link that this joint connects to. There will always be such a link. | |
double | getDistanceFactor () const |
Get the factor that should be applied to the value returned by distance() when that value is used in compound distances. | |
virtual double | getMaximumExtent (const Bounds &other_bounds) const =0 |
Get the extent of the state space (the maximum value distance() can ever report) | |
double | getMaximumExtent () const |
double | getMaximumVelocity () const |
Get the maximum velocity of this joint. If the result is zero, the value is assumed not to be specified. | |
const JointModel * | getMimic () const |
Get the joint this one is mimicking. | |
double | getMimicFactor () const |
If mimicking a joint, this is the multiplicative factor for that joint's value. | |
double | getMimicOffset () const |
If mimicking a joint, this is the offset added to that joint's value. | |
const std::vector< const JointModel * > & | getMimicRequests () const |
The joint models whose values would be modified if the value of this joint changed. | |
const std::string & | getName () const |
Get the name of the joint. | |
const LinkModel * | getParentLinkModel () const |
Get the link that this joint connects to. The robot is assumed to start with a joint, so the root joint will return a NULL pointer here. | |
virtual unsigned int | getStateSpaceDimension () const =0 |
Get the dimension of the state space that corresponds to this joint. | |
int | getTreeIndex () const |
The index of this joint when traversing the kinematic tree in depth first fashion. | |
JointType | getType () const |
Get the type of joint. | |
std::string | getTypeName () const |
Get the type of joint as a string. | |
virtual void | interpolate (const std::vector< double > &from, const std::vector< double > &to, const double t, std::vector< double > &state) const =0 |
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. The memory location of state is not required to be different from the memory of either from or to. | |
bool | isPassive () const |
Check if this joint is passive. | |
JointModel (const std::string &name) | |
Construct a joint named name. | |
void | setDistanceFactor (double factor) |
Set the factor that should be applied to the value returned by distance() when that value is used in compound distances. | |
virtual | ~JointModel () |
Reason about the variables that make up this joint | |
const std::vector< std::string > & | getVariableNames () const |
Get the names of the variables that make up this joint, in the order they appear in corresponding states. For single DOF joints, this will be just the joint name. For multi-DOF joints these will be the joint name followed by "/", followed by the local names of the variables. | |
bool | hasVariable (const std::string &variable) const |
Check if a particular variable is known to this joint. | |
unsigned int | getVariableCount () const |
Get the number of variables that describe this joint. | |
const std::map< std::string, unsigned int > & | getVariableIndexMap () const |
The set of variables that make up the state value of a joint are stored in some order. This map gives the position of each variable in that order, for each variable name. | |
const std::vector< std::string > & | getLocalVariableNames () const |
Get the local names of the variable that make up the joint (suffixes that are attached to joint names to construct the variable names). For single DOF joints, this will be empty. | |
Functionality specific to computing state values | |
void | getVariableDefaultValues (std::map< std::string, double > &values) const |
Provide defaults value for the joint variables, given the default joint variable bounds (maintained internally). Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The map is NOT cleared; elements are only added (or overwritten). | |
void | getVariableDefaultValues (std::map< std::string, double > &values, const Bounds &other_bounds) const |
Provide a default value for the joint variables given the joint bounds. Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The map is NOT cleared; elements are only added (or overwritten). | |
void | getVariableDefaultValues (std::vector< double > &values) const |
Provide a default value for the joint given the default joint variable bounds (maintained internally). Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The vector is NOT cleared; elements are only added with push_back. | |
virtual void | getVariableDefaultValues (std::vector< double > &values, const Bounds &other_bounds) const =0 |
Provide a default value for the joint given the joint variable bounds. Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The vector is NOT cleared; elements are only added with push_back. | |
void | getVariableRandomValues (random_numbers::RandomNumberGenerator &rng, std::map< std::string, double > &values) const |
Provide random values for the joint variables (within default bounds). The map is NOT cleared; elements are only added (or overwritten). | |
void | getVariableRandomValues (random_numbers::RandomNumberGenerator &rng, std::map< std::string, double > &values, const Bounds &other_bounds) const |
Provide random values for the joint variables (within specified bounds). The map is NOT cleared; elements are only added (or overwritten). | |
void | getVariableRandomValues (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values) const |
Provide random values for the joint variables (within default bounds). The vector is NOT cleared; elements are only added with push_back. | |
virtual void | getVariableRandomValues (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const Bounds &other_bounds) const =0 |
Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back. | |
void | getVariableRandomValuesNearBy (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const std::vector< double > &near, const double distance) const |
Provide random values for the joint variables (within default bounds). The vector is NOT cleared; elements are only added with push_back. | |
virtual void | getVariableRandomValuesNearBy (random_numbers::RandomNumberGenerator &rng, std::vector< double > &values, const Bounds &other_bounds, const std::vector< double > &near, const double distance) const =0 |
Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back. | |
Functionality specific to verifying bounds | |
bool | satisfiesBounds (const std::vector< double > &values, double margin=0.0) const |
Check if the set of values for the variables of this joint are within bounds. | |
virtual bool | satisfiesBounds (const std::vector< double > &values, const Bounds &other_bounds, double margin) const =0 |
Check if the set of values for the variables of this joint are within bounds, up to some margin. | |
void | enforceBounds (std::vector< double > &values) const |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi. | |
virtual void | enforceBounds (std::vector< double > &values, const Bounds &other_bounds) const =0 |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi. | |
bool | getVariableBounds (const std::string &variable, std::pair< double, double > &bounds) const |
Get the lower and upper bounds for a variable. Return false if the variable was not found. | |
const Bounds & | getVariableBounds () const |
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames() | |
bool | setVariableBounds (const std::string &variable, const std::pair< double, double > &bounds) |
Set the lower and upper bounds for a variable. Return false if the variable was not found. | |
const std::vector < moveit_msgs::JointLimits > & | getVariableDefaultLimits () const |
Get variable limits as a message type. | |
void | setVariableLimits (const std::vector< moveit_msgs::JointLimits > &jlim) |
Override joint limits. | |
const std::vector < moveit_msgs::JointLimits > & | getVariableLimits () const |
Get the joint limits specified by the user with setLimits() or the default joint limits using getVariableLimits(), if no joint limits were specified. | |
virtual void | computeDefaultVariableLimits () |
Computing transforms | |
virtual void | computeTransform (const std::vector< double > &joint_values, Eigen::Affine3d &transf) const =0 |
Given the joint values for a joint, compute the corresponding transform. | |
virtual void | computeJointStateValues (const Eigen::Affine3d &transform, std::vector< double > &joint_values) const =0 |
Given the transform generated by joint, compute the corresponding joint values. | |
virtual void | updateTransform (const std::vector< double > &joint_values, Eigen::Affine3d &transf) const =0 |
Update a transform so that it corresponds to the new joint values assuming that transf was previously set to identity and that only calls to updateTransform() were issued afterwards. | |
Protected Attributes | |
LinkModel * | child_link_model_ |
The link after this joint. | |
std::vector < moveit_msgs::JointLimits > | default_limits_ |
Default limits for this joint. | |
double | distance_factor_ |
The factor applied to the distance between two joint states. | |
std::vector< std::string > | local_variable_names_ |
The local names to use for the variables that make up this joint. | |
double | max_velocity_ |
The maximum velocity of this joint. If zero, the value is considered not to be specified. | |
JointModel * | mimic_ |
The joint this one mimics (NULL for joints that do not mimic) | |
double | mimic_factor_ |
The offset to the mimic joint. | |
double | mimic_offset_ |
The multiplier to the mimic joint. | |
std::vector< const JointModel * > | mimic_requests_ |
The set of joints that should get a value copied to them when this joint changes. | |
std::string | name_ |
Name of the joint. | |
LinkModel * | parent_link_model_ |
The link before this joint. | |
bool | passive_ |
Specify whether this joint is marked as passive in the SRDF. | |
int | tree_index_ |
The index assigned to this joint when traversing the kinematic tree in depth first fashion. | |
JointType | type_ |
The type of joint. | |
std::vector < moveit_msgs::JointLimits > | user_specified_limits_ |
User specified limits for this joint. | |
Bounds | variable_bounds_ |
The bounds for each variable (low, high) in the same order as variable_names_. | |
std::map< std::string, unsigned int > | variable_index_ |
Map from variable names to the corresponding index in variable_names_. | |
std::vector< std::string > | variable_names_ |
The full names to use for the variables that make up this joint. | |
Friends | |
class | RobotModel |
A joint from the robot. Models the transform that this joint applies in the kinematic chain. A joint consists of multiple variables. In the simplest case, when the joint is a single DOF, there is only one variable and its name is the same as the joint's name. For multi-DOF joints, each variable has a local name (e.g., x, y) but the full variable name as seen from the outside of this class is a concatenation of the "joint name"/"local name" (e.g., a joint named 'base' with local variables 'x' and 'y' will store its full variable names as 'base/x' and 'base/y'). Local names are never used to reference variables directly.
Definition at line 66 of file joint_model.h.
typedef std::vector<std::pair<double, double> > robot_model::JointModel::Bounds |
The datatype for the joint bounds.
Definition at line 78 of file joint_model.h.
The different types of joints we support.
Definition at line 72 of file joint_model.h.
robot_model::JointModel::JointModel | ( | const std::string & | name | ) |
Construct a joint named name.
Definition at line 40 of file joint_model.cpp.
robot_model::JointModel::~JointModel | ( | ) | [virtual] |
Definition at line 46 of file joint_model.cpp.
void robot_model::JointModel::computeDefaultVariableLimits | ( | ) | [virtual] |
Reimplemented in robot_model::RevoluteJointModel.
Definition at line 92 of file joint_model.cpp.
virtual void robot_model::JointModel::computeJointStateValues | ( | const Eigen::Affine3d & | transform, |
std::vector< double > & | joint_values | ||
) | const [pure virtual] |
Given the transform generated by joint, compute the corresponding joint values.
Implemented in robot_model::PlanarJointModel, robot_model::RevoluteJointModel, robot_model::FixedJointModel, robot_model::FloatingJointModel, and robot_model::PrismaticJointModel.
virtual void robot_model::JointModel::computeTransform | ( | const std::vector< double > & | joint_values, |
Eigen::Affine3d & | transf | ||
) | const [pure virtual] |
Given the joint values for a joint, compute the corresponding transform.
Implemented in robot_model::PlanarJointModel, robot_model::RevoluteJointModel, robot_model::FixedJointModel, robot_model::FloatingJointModel, and robot_model::PrismaticJointModel.
virtual double robot_model::JointModel::distance | ( | const std::vector< double > & | values1, |
const std::vector< double > & | values2 | ||
) | const [pure virtual] |
Compute the distance between two joint states of the same model (represented by the variable values)
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::PrismaticJointModel, robot_model::RevoluteJointModel, and robot_model::FloatingJointModel.
void robot_model::JointModel::enforceBounds | ( | std::vector< double > & | values | ) | const [inline] |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi.
Definition at line 245 of file joint_model.h.
virtual void robot_model::JointModel::enforceBounds | ( | std::vector< double > & | values, |
const Bounds & | other_bounds | ||
) | const [pure virtual] |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi.
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::FloatingJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
const LinkModel* robot_model::JointModel::getChildLinkModel | ( | ) | const [inline] |
Get the link that this joint connects to. There will always be such a link.
Definition at line 128 of file joint_model.h.
double robot_model::JointModel::getDistanceFactor | ( | ) | const [inline] |
Get the factor that should be applied to the value returned by distance() when that value is used in compound distances.
Definition at line 288 of file joint_model.h.
const std::vector<std::string>& robot_model::JointModel::getLocalVariableNames | ( | ) | const [inline] |
Get the local names of the variable that make up the joint (suffixes that are attached to joint names to construct the variable names). For single DOF joints, this will be empty.
Definition at line 165 of file joint_model.h.
virtual double robot_model::JointModel::getMaximumExtent | ( | const Bounds & | other_bounds | ) | const [pure virtual] |
Get the extent of the state space (the maximum value distance() can ever report)
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::PrismaticJointModel, robot_model::RevoluteJointModel, and robot_model::FloatingJointModel.
double robot_model::JointModel::getMaximumExtent | ( | ) | const [inline] |
Definition at line 346 of file joint_model.h.
double robot_model::JointModel::getMaximumVelocity | ( | ) | const [inline] |
Get the maximum velocity of this joint. If the result is zero, the value is assumed not to be specified.
Definition at line 333 of file joint_model.h.
const JointModel* robot_model::JointModel::getMimic | ( | ) | const [inline] |
Get the joint this one is mimicking.
Definition at line 303 of file joint_model.h.
double robot_model::JointModel::getMimicFactor | ( | ) | const [inline] |
If mimicking a joint, this is the multiplicative factor for that joint's value.
Definition at line 315 of file joint_model.h.
double robot_model::JointModel::getMimicOffset | ( | ) | const [inline] |
If mimicking a joint, this is the offset added to that joint's value.
Definition at line 309 of file joint_model.h.
const std::vector<const JointModel*>& robot_model::JointModel::getMimicRequests | ( | ) | const [inline] |
The joint models whose values would be modified if the value of this joint changed.
Definition at line 321 of file joint_model.h.
const std::string& robot_model::JointModel::getName | ( | ) | const [inline] |
Get the name of the joint.
Definition at line 87 of file joint_model.h.
const LinkModel* robot_model::JointModel::getParentLinkModel | ( | ) | const [inline] |
Get the link that this joint connects to. The robot is assumed to start with a joint, so the root joint will return a NULL pointer here.
Definition at line 122 of file joint_model.h.
virtual unsigned int robot_model::JointModel::getStateSpaceDimension | ( | ) | const [pure virtual] |
Get the dimension of the state space that corresponds to this joint.
Implemented in robot_model::FloatingJointModel, robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
int robot_model::JointModel::getTreeIndex | ( | ) | const [inline] |
The index of this joint when traversing the kinematic tree in depth first fashion.
Definition at line 114 of file joint_model.h.
JointType robot_model::JointModel::getType | ( | ) | const [inline] |
Get the type of joint.
Definition at line 93 of file joint_model.h.
std::string robot_model::JointModel::getTypeName | ( | ) | const [inline] |
Get the type of joint as a string.
Definition at line 99 of file joint_model.h.
bool robot_model::JointModel::getVariableBounds | ( | const std::string & | variable, |
std::pair< double, double > & | bounds | ||
) | const |
Get the lower and upper bounds for a variable. Return false if the variable was not found.
Definition at line 50 of file joint_model.cpp.
const Bounds& robot_model::JointModel::getVariableBounds | ( | ) | const [inline] |
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()
Definition at line 257 of file joint_model.h.
unsigned int robot_model::JointModel::getVariableCount | ( | ) | const [inline] |
Get the number of variables that describe this joint.
Definition at line 151 of file joint_model.h.
const std::vector<moveit_msgs::JointLimits>& robot_model::JointModel::getVariableDefaultLimits | ( | ) | const [inline] |
Get variable limits as a message type.
Definition at line 266 of file joint_model.h.
void robot_model::JointModel::getVariableDefaultValues | ( | std::map< std::string, double > & | values | ) | const [inline] |
Provide defaults value for the joint variables, given the default joint variable bounds (maintained internally). Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The map is NOT cleared; elements are only added (or overwritten).
Definition at line 178 of file joint_model.h.
void robot_model::JointModel::getVariableDefaultValues | ( | std::map< std::string, double > & | values, |
const Bounds & | other_bounds | ||
) | const |
Provide a default value for the joint variables given the joint bounds. Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The map is NOT cleared; elements are only added (or overwritten).
Definition at line 74 of file joint_model.cpp.
void robot_model::JointModel::getVariableDefaultValues | ( | std::vector< double > & | values | ) | const [inline] |
Provide a default value for the joint given the default joint variable bounds (maintained internally). Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The vector is NOT cleared; elements are only added with push_back.
Definition at line 191 of file joint_model.h.
virtual void robot_model::JointModel::getVariableDefaultValues | ( | std::vector< double > & | values, |
const Bounds & | other_bounds | ||
) | const [pure virtual] |
Provide a default value for the joint given the joint variable bounds. Most joints will use the default implementation provided in this base class, but the quaternion for example needs a different implementation. The vector is NOT cleared; elements are only added with push_back.
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::FloatingJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
const std::map<std::string, unsigned int>& robot_model::JointModel::getVariableIndexMap | ( | ) | const [inline] |
The set of variables that make up the state value of a joint are stored in some order. This map gives the position of each variable in that order, for each variable name.
Definition at line 158 of file joint_model.h.
const std::vector<moveit_msgs::JointLimits>& robot_model::JointModel::getVariableLimits | ( | ) | const [inline] |
Get the joint limits specified by the user with setLimits() or the default joint limits using getVariableLimits(), if no joint limits were specified.
Reimplemented in robot_model::PlanarJointModel.
Definition at line 275 of file joint_model.h.
const std::vector<std::string>& robot_model::JointModel::getVariableNames | ( | ) | const [inline] |
Get the names of the variables that make up this joint, in the order they appear in corresponding states. For single DOF joints, this will be just the joint name. For multi-DOF joints these will be the joint name followed by "/", followed by the local names of the variables.
Definition at line 139 of file joint_model.h.
void robot_model::JointModel::getVariableRandomValues | ( | random_numbers::RandomNumberGenerator & | rng, |
std::map< std::string, double > & | values | ||
) | const [inline] |
Provide random values for the joint variables (within default bounds). The map is NOT cleared; elements are only added (or overwritten).
Definition at line 202 of file joint_model.h.
void robot_model::JointModel::getVariableRandomValues | ( | random_numbers::RandomNumberGenerator & | rng, |
std::map< std::string, double > & | values, | ||
const Bounds & | other_bounds | ||
) | const |
Provide random values for the joint variables (within specified bounds). The map is NOT cleared; elements are only added (or overwritten).
Definition at line 83 of file joint_model.cpp.
void robot_model::JointModel::getVariableRandomValues | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values | ||
) | const [inline] |
Provide random values for the joint variables (within default bounds). The vector is NOT cleared; elements are only added with push_back.
Definition at line 211 of file joint_model.h.
virtual void robot_model::JointModel::getVariableRandomValues | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values, | ||
const Bounds & | other_bounds | ||
) | const [pure virtual] |
Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back.
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::FloatingJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
void robot_model::JointModel::getVariableRandomValuesNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values, | ||
const std::vector< double > & | near, | ||
const double | distance | ||
) | const [inline] |
Provide random values for the joint variables (within default bounds). The vector is NOT cleared; elements are only added with push_back.
Definition at line 220 of file joint_model.h.
virtual void robot_model::JointModel::getVariableRandomValuesNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
std::vector< double > & | values, | ||
const Bounds & | other_bounds, | ||
const std::vector< double > & | near, | ||
const double | distance | ||
) | const [pure virtual] |
Provide random values for the joint variables (within specified bounds). The vector is NOT cleared; elements are only added with push_back.
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::FloatingJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
bool robot_model::JointModel::hasVariable | ( | const std::string & | variable | ) | const [inline] |
Check if a particular variable is known to this joint.
Definition at line 145 of file joint_model.h.
virtual void robot_model::JointModel::interpolate | ( | const std::vector< double > & | from, |
const std::vector< double > & | to, | ||
const double | t, | ||
std::vector< double > & | state | ||
) | const [pure virtual] |
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state. The memory location of state is not required to be different from the memory of either from or to.
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::FloatingJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
bool robot_model::JointModel::isPassive | ( | ) | const [inline] |
Check if this joint is passive.
Definition at line 327 of file joint_model.h.
bool robot_model::JointModel::satisfiesBounds | ( | const std::vector< double > & | values, |
double | margin = 0.0 |
||
) | const [inline] |
Check if the set of values for the variables of this joint are within bounds.
Definition at line 236 of file joint_model.h.
virtual bool robot_model::JointModel::satisfiesBounds | ( | const std::vector< double > & | values, |
const Bounds & | other_bounds, | ||
double | margin | ||
) | const [pure virtual] |
Check if the set of values for the variables of this joint are within bounds, up to some margin.
Implemented in robot_model::FixedJointModel, robot_model::PlanarJointModel, robot_model::FloatingJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
void robot_model::JointModel::setDistanceFactor | ( | double | factor | ) | [inline] |
Set the factor that should be applied to the value returned by distance() when that value is used in compound distances.
Definition at line 294 of file joint_model.h.
bool robot_model::JointModel::setVariableBounds | ( | const std::string & | variable, |
const std::pair< double, double > & | bounds | ||
) |
Set the lower and upper bounds for a variable. Return false if the variable was not found.
Definition at line 62 of file joint_model.cpp.
void robot_model::JointModel::setVariableLimits | ( | const std::vector< moveit_msgs::JointLimits > & | jlim | ) |
Override joint limits.
Definition at line 113 of file joint_model.cpp.
virtual void robot_model::JointModel::updateTransform | ( | const std::vector< double > & | joint_values, |
Eigen::Affine3d & | transf | ||
) | const [pure virtual] |
Update a transform so that it corresponds to the new joint values assuming that transf was previously set to identity and that only calls to updateTransform() were issued afterwards.
Implemented in robot_model::PlanarJointModel, robot_model::RevoluteJointModel, robot_model::FixedJointModel, robot_model::FloatingJointModel, and robot_model::PrismaticJointModel.
friend class RobotModel [friend] |
Reimplemented in robot_model::FixedJointModel, robot_model::FloatingJointModel, robot_model::PlanarJointModel, robot_model::PrismaticJointModel, and robot_model::RevoluteJointModel.
Definition at line 68 of file joint_model.h.
LinkModel* robot_model::JointModel::child_link_model_ [protected] |
The link after this joint.
Definition at line 394 of file joint_model.h.
std::vector<moveit_msgs::JointLimits> robot_model::JointModel::default_limits_ [protected] |
Default limits for this joint.
Definition at line 415 of file joint_model.h.
double robot_model::JointModel::distance_factor_ [protected] |
The factor applied to the distance between two joint states.
Definition at line 412 of file joint_model.h.
std::vector<std::string> robot_model::JointModel::local_variable_names_ [protected] |
The local names to use for the variables that make up this joint.
Definition at line 376 of file joint_model.h.
double robot_model::JointModel::max_velocity_ [protected] |
The maximum velocity of this joint. If zero, the value is considered not to be specified.
Definition at line 385 of file joint_model.h.
JointModel* robot_model::JointModel::mimic_ [protected] |
The joint this one mimics (NULL for joints that do not mimic)
Definition at line 397 of file joint_model.h.
double robot_model::JointModel::mimic_factor_ [protected] |
The offset to the mimic joint.
Definition at line 400 of file joint_model.h.
double robot_model::JointModel::mimic_offset_ [protected] |
The multiplier to the mimic joint.
Definition at line 403 of file joint_model.h.
std::vector<const JointModel*> robot_model::JointModel::mimic_requests_ [protected] |
The set of joints that should get a value copied to them when this joint changes.
Definition at line 406 of file joint_model.h.
std::string robot_model::JointModel::name_ [protected] |
Name of the joint.
Definition at line 370 of file joint_model.h.
LinkModel* robot_model::JointModel::parent_link_model_ [protected] |
The link before this joint.
Definition at line 391 of file joint_model.h.
bool robot_model::JointModel::passive_ [protected] |
Specify whether this joint is marked as passive in the SRDF.
Definition at line 409 of file joint_model.h.
int robot_model::JointModel::tree_index_ [protected] |
The index assigned to this joint when traversing the kinematic tree in depth first fashion.
Definition at line 421 of file joint_model.h.
JointType robot_model::JointModel::type_ [protected] |
The type of joint.
Definition at line 373 of file joint_model.h.
std::vector<moveit_msgs::JointLimits> robot_model::JointModel::user_specified_limits_ [protected] |
User specified limits for this joint.
Definition at line 418 of file joint_model.h.
Bounds robot_model::JointModel::variable_bounds_ [protected] |
The bounds for each variable (low, high) in the same order as variable_names_.
Definition at line 382 of file joint_model.h.
std::map<std::string, unsigned int> robot_model::JointModel::variable_index_ [protected] |
Map from variable names to the corresponding index in variable_names_.
Definition at line 388 of file joint_model.h.
std::vector<std::string> robot_model::JointModel::variable_names_ [protected] |
The full names to use for the variables that make up this joint.
Definition at line 379 of file joint_model.h.