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 < VariableBounds > | 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 | |
void | addDescendantJointModel (const JointModel *joint) |
void | addDescendantLinkModel (const LinkModel *link) |
void | addMimicRequest (const JointModel *joint) |
Notify this joint that there is another joint that mimics it. | |
virtual double | distance (const double *value1, const double *value2) 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. | |
const std::vector< const JointModel * > & | getDescendantJointModels () const |
Get all the joint models that descend from this joint, in the kinematic tree. | |
const std::vector< const LinkModel * > & | getDescendantLinkModels () const |
Get all the link models that descend from this joint, in the kinematic tree. | |
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 |
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 std::vector< const JointModel * > & | getNonFixedDescendantJointModels () const |
Get all the non-fixed joint models that descend from this joint, in the kinematic tree. | |
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. | |
JointType | getType () const |
Get the type of joint. | |
std::string | getTypeName () const |
Get the type of joint as a string. | |
virtual void | interpolate (const double *from, const double *to, const double t, 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 | setChildLinkModel (const LinkModel *link) |
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. | |
void | setMimic (const JointModel *mimic, double factor, double offset) |
Mark this joint as mimicking mimic using factor and offset. | |
void | setParentLinkModel (const LinkModel *link) |
void | setPassive (bool flag) |
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. | |
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. | |
bool | hasVariable (const std::string &variable) const |
Check if a particular variable is known to this joint. | |
std::size_t | getVariableCount () const |
Get the number of variables that describe this joint. | |
int | getFirstVariableIndex () const |
Get the index of this joint's first variable within the full robot state. | |
void | setFirstVariableIndex (int index) |
Set the index of this joint's first variable within the full robot state. | |
int | getJointIndex () const |
Get the index of this joint within the robot model. | |
void | setJointIndex (int index) |
Set the index of this joint within the robot model. | |
int | getLocalVariableIndex (const std::string &variable) const |
Get the index of the variable within this joint. | |
Functionality specific to computing state values | |
void | getVariableDefaultPositions (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. Enough memory is assumed to be allocated. | |
virtual void | getVariableDefaultPositions (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. Enough memory is assumed to be allocated. | |
void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values) const |
Provide random values for the joint variables (within default bounds). Enough memory is assumed to be allocated. | |
virtual void | getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const =0 |
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const double *near, const double distance) const |
Provide random values for the joint variables (within default bounds). Enough memory is assumed to be allocated. | |
virtual void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const =0 |
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated. | |
Functionality specific to verifying bounds | |
bool | satisfiesPositionBounds (const double *values, double margin=0.0) const |
Check if the set of values for the variables of this joint are within bounds. | |
virtual bool | satisfiesPositionBounds (const double *values, const Bounds &other_bounds, double margin) const =0 |
Check if the set of position values for the variables of this joint are within bounds, up to some margin. | |
bool | enforcePositionBounds (double *values) const |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi. Returns true if changes were made. | |
virtual bool | enforcePositionBounds (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. Return true if changes were made. | |
bool | satisfiesVelocityBounds (const double *values, double margin=0.0) const |
Check if the set of velocities for the variables of this joint are within bounds. | |
virtual bool | satisfiesVelocityBounds (const double *values, const Bounds &other_bounds, double margin) const |
Check if the set of velocities for the variables of this joint are within bounds, up to some margin. | |
bool | enforceVelocityBounds (double *values) const |
Force the specified velocities to be within bounds. Return true if changes were made. | |
virtual bool | enforceVelocityBounds (double *values, const Bounds &other_bounds) const |
Force the specified velocities to be inside bounds. Return true if changes were made. | |
const VariableBounds & | getVariableBounds (const std::string &variable) const |
Get the bounds for a variable. Throw an exception 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() | |
void | setVariableBounds (const std::string &variable, const VariableBounds &bounds) |
Set the lower and upper bounds for a variable. Throw an exception if the variable was not found. | |
void | setVariableBounds (const std::vector< moveit_msgs::JointLimits > &jlim) |
Override joint limits loaded from URDF. Unknown variables are ignored. | |
const std::vector < moveit_msgs::JointLimits > & | getVariableBoundsMsg () const |
Get the joint limits known to this model, as a message. | |
Computing transforms | |
virtual void | computeTransform (const double *joint_values, Eigen::Affine3d &transf) const =0 |
Given the joint values for a joint, compute the corresponding transform. | |
virtual void | computeVariablePositions (const Eigen::Affine3d &transform, double *joint_values) const =0 |
Given the transform generated by joint, compute the corresponding joint values. | |
Protected Member Functions | |
void | computeVariableBoundsMsg () |
Protected Attributes | |
const LinkModel * | child_link_model_ |
The link after this joint. | |
std::vector< const JointModel * > | descendant_joint_models_ |
Pointers to all the joints that follow this one in the kinematic tree (including mimic joints) | |
std::vector< const LinkModel * > | descendant_link_models_ |
Pointers to all the links that will be moved if this joint changes value. | |
double | distance_factor_ |
The factor applied to the distance between two joint states. | |
int | first_variable_index_ |
The index of this joint's first variable, in the complete robot state. | |
int | joint_index_ |
Index for this joint in the array of joints of the complete model. | |
std::vector< std::string > | local_variable_names_ |
The local names to use for the variables that make up this joint. | |
const 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. | |
std::vector< const JointModel * > | non_fixed_descendant_joint_models_ |
Pointers to all the joints that follow this one in the kinematic tree, including mimic joints, but excluding fixed joints. | |
const LinkModel * | parent_link_model_ |
The link before this joint. | |
bool | passive_ |
Specify whether this joint is marked as passive in the SRDF. | |
JointType | type_ |
The type of joint. | |
Bounds | variable_bounds_ |
The bounds for each variable (low, high) in the same order as variable_names_. | |
std::vector < moveit_msgs::JointLimits > | variable_bounds_msg_ |
VariableIndexMap | variable_index_map_ |
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within the JointModel only) | |
std::vector< std::string > | variable_names_ |
The full names to use for the variables that make up this joint. |
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 110 of file joint_model.h.
typedef std::vector<VariableBounds> moveit::core::JointModel::Bounds |
The datatype for the joint bounds.
Definition at line 121 of file joint_model.h.
The different types of joints we support.
Definition at line 115 of file joint_model.h.
moveit::core::JointModel::JointModel | ( | const std::string & | name | ) |
Construct a joint named name.
Definition at line 43 of file joint_model.cpp.
moveit::core::JointModel::~JointModel | ( | ) | [virtual] |
Definition at line 58 of file joint_model.cpp.
void moveit::core::JointModel::addDescendantJointModel | ( | const JointModel * | joint | ) |
Definition at line 183 of file joint_model.cpp.
void moveit::core::JointModel::addDescendantLinkModel | ( | const LinkModel * | link | ) |
Definition at line 190 of file joint_model.cpp.
void moveit::core::JointModel::addMimicRequest | ( | const JointModel * | joint | ) |
Notify this joint that there is another joint that mimics it.
Definition at line 178 of file joint_model.cpp.
virtual void moveit::core::JointModel::computeTransform | ( | const double * | joint_values, |
Eigen::Affine3d & | transf | ||
) | const [pure virtual] |
Given the joint values for a joint, compute the corresponding transform.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
void moveit::core::JointModel::computeVariableBoundsMsg | ( | ) | [protected] |
Definition at line 153 of file joint_model.cpp.
virtual void moveit::core::JointModel::computeVariablePositions | ( | const Eigen::Affine3d & | transform, |
double * | joint_values | ||
) | const [pure virtual] |
Given the transform generated by joint, compute the corresponding joint values.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
virtual double moveit::core::JointModel::distance | ( | const double * | value1, |
const double * | value2 | ||
) | const [pure virtual] |
Compute the distance between two joint states of the same model (represented by the variable values)
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
bool moveit::core::JointModel::enforcePositionBounds | ( | 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. Returns true if changes were made.
Definition at line 278 of file joint_model.h.
virtual bool moveit::core::JointModel::enforcePositionBounds | ( | 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. Return true if changes were made.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
bool moveit::core::JointModel::enforceVelocityBounds | ( | double * | values | ) | const [inline] |
Force the specified velocities to be within bounds. Return true if changes were made.
Definition at line 297 of file joint_model.h.
bool moveit::core::JointModel::enforceVelocityBounds | ( | double * | values, |
const Bounds & | other_bounds | ||
) | const [virtual] |
Force the specified velocities to be inside bounds. Return true if changes were made.
Definition at line 84 of file joint_model.cpp.
const LinkModel* moveit::core::JointModel::getChildLinkModel | ( | ) | const [inline] |
Get the link that this joint connects to. There will always be such a link.
Definition at line 152 of file joint_model.h.
const std::vector<const JointModel*>& moveit::core::JointModel::getDescendantJointModels | ( | ) | const [inline] |
Get all the joint models that descend from this joint, in the kinematic tree.
Definition at line 385 of file joint_model.h.
const std::vector<const LinkModel*>& moveit::core::JointModel::getDescendantLinkModels | ( | ) | const [inline] |
Get all the link models that descend from this joint, in the kinematic tree.
Definition at line 379 of file joint_model.h.
double moveit::core::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 332 of file joint_model.h.
int moveit::core::JointModel::getFirstVariableIndex | ( | ) | const [inline] |
Get the index of this joint's first variable within the full robot state.
Definition at line 198 of file joint_model.h.
int moveit::core::JointModel::getJointIndex | ( | ) | const [inline] |
Get the index of this joint within the robot model.
Definition at line 210 of file joint_model.h.
int moveit::core::JointModel::getLocalVariableIndex | ( | const std::string & | variable | ) | const |
Get the index of the variable within this joint.
Definition at line 76 of file joint_model.cpp.
const std::vector<std::string>& moveit::core::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 180 of file joint_model.h.
virtual double moveit::core::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 moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
double moveit::core::JointModel::getMaximumExtent | ( | ) | const [inline] |
Definition at line 415 of file joint_model.h.
const JointModel* moveit::core::JointModel::getMimic | ( | ) | const [inline] |
Get the joint this one is mimicking.
Definition at line 347 of file joint_model.h.
double moveit::core::JointModel::getMimicFactor | ( | ) | const [inline] |
If mimicking a joint, this is the multiplicative factor for that joint's value.
Definition at line 359 of file joint_model.h.
double moveit::core::JointModel::getMimicOffset | ( | ) | const [inline] |
If mimicking a joint, this is the offset added to that joint's value.
Definition at line 353 of file joint_model.h.
const std::vector<const JointModel*>& moveit::core::JointModel::getMimicRequests | ( | ) | const [inline] |
The joint models whose values would be modified if the value of this joint changed.
Definition at line 368 of file joint_model.h.
const std::string& moveit::core::JointModel::getName | ( | ) | const [inline] |
Get the name of the joint.
Definition at line 129 of file joint_model.h.
const std::vector<const JointModel*>& moveit::core::JointModel::getNonFixedDescendantJointModels | ( | ) | const [inline] |
Get all the non-fixed joint models that descend from this joint, in the kinematic tree.
Definition at line 391 of file joint_model.h.
const LinkModel* moveit::core::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 146 of file joint_model.h.
virtual unsigned int moveit::core::JointModel::getStateSpaceDimension | ( | ) | const [pure virtual] |
Get the dimension of the state space that corresponds to this joint.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
JointType moveit::core::JointModel::getType | ( | ) | const [inline] |
Get the type of joint.
Definition at line 135 of file joint_model.h.
std::string moveit::core::JointModel::getTypeName | ( | ) | const |
Get the type of joint as a string.
Definition at line 62 of file joint_model.cpp.
const moveit::core::VariableBounds & moveit::core::JointModel::getVariableBounds | ( | const std::string & | variable | ) | const |
Get the bounds for a variable. Throw an exception if the variable was not found.
Definition at line 113 of file joint_model.cpp.
const Bounds& moveit::core::JointModel::getVariableBounds | ( | ) | const [inline] |
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()
Definition at line 309 of file joint_model.h.
const std::vector<moveit_msgs::JointLimits>& moveit::core::JointModel::getVariableBoundsMsg | ( | ) | const [inline] |
Get the joint limits known to this model, as a message.
Definition at line 321 of file joint_model.h.
std::size_t moveit::core::JointModel::getVariableCount | ( | ) | const [inline] |
Get the number of variables that describe this joint.
Definition at line 192 of file joint_model.h.
void moveit::core::JointModel::getVariableDefaultPositions | ( | 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. Enough memory is assumed to be allocated.
Definition at line 232 of file joint_model.h.
virtual void moveit::core::JointModel::getVariableDefaultPositions | ( | 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. Enough memory is assumed to be allocated.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
const std::vector<std::string>& moveit::core::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 173 of file joint_model.h.
void moveit::core::JointModel::getVariableRandomPositions | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values | ||
) | const [inline] |
Provide random values for the joint variables (within default bounds). Enough memory is assumed to be allocated.
Definition at line 243 of file joint_model.h.
virtual void moveit::core::JointModel::getVariableRandomPositions | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values, | ||
const Bounds & | other_bounds | ||
) | const [pure virtual] |
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
void moveit::core::JointModel::getVariableRandomPositionsNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values, | ||
const double * | near, | ||
const double | distance | ||
) | const [inline] |
Provide random values for the joint variables (within default bounds). Enough memory is assumed to be allocated.
Definition at line 252 of file joint_model.h.
virtual void moveit::core::JointModel::getVariableRandomPositionsNearBy | ( | random_numbers::RandomNumberGenerator & | rng, |
double * | values, | ||
const Bounds & | other_bounds, | ||
const double * | near, | ||
const double | distance | ||
) | const [pure virtual] |
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
bool moveit::core::JointModel::hasVariable | ( | const std::string & | variable | ) | const [inline] |
Check if a particular variable is known to this joint.
Definition at line 186 of file joint_model.h.
virtual void moveit::core::JointModel::interpolate | ( | const double * | from, |
const double * | to, | ||
const double | t, | ||
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 moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
bool moveit::core::JointModel::isPassive | ( | ) | const [inline] |
Check if this joint is passive.
Definition at line 397 of file joint_model.h.
bool moveit::core::JointModel::satisfiesPositionBounds | ( | const 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 268 of file joint_model.h.
virtual bool moveit::core::JointModel::satisfiesPositionBounds | ( | const double * | values, |
const Bounds & | other_bounds, | ||
double | margin | ||
) | const [pure virtual] |
Check if the set of position values for the variables of this joint are within bounds, up to some margin.
Implemented in moveit::core::PrismaticJointModel, moveit::core::FloatingJointModel, moveit::core::PlanarJointModel, moveit::core::RevoluteJointModel, and moveit::core::FixedJointModel.
bool moveit::core::JointModel::satisfiesVelocityBounds | ( | const double * | values, |
double | margin = 0.0 |
||
) | const [inline] |
Check if the set of velocities for the variables of this joint are within bounds.
Definition at line 288 of file joint_model.h.
bool moveit::core::JointModel::satisfiesVelocityBounds | ( | const double * | values, |
const Bounds & | other_bounds, | ||
double | margin | ||
) | const [virtual] |
Check if the set of velocities for the variables of this joint are within bounds, up to some margin.
Definition at line 102 of file joint_model.cpp.
void moveit::core::JointModel::setChildLinkModel | ( | const LinkModel * | link | ) | [inline] |
Definition at line 162 of file joint_model.h.
void moveit::core::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 338 of file joint_model.h.
void moveit::core::JointModel::setFirstVariableIndex | ( | int | index | ) | [inline] |
Set the index of this joint's first variable within the full robot state.
Definition at line 204 of file joint_model.h.
void moveit::core::JointModel::setJointIndex | ( | int | index | ) | [inline] |
Set the index of this joint within the robot model.
Definition at line 216 of file joint_model.h.
void moveit::core::JointModel::setMimic | ( | const JointModel * | mimic, |
double | factor, | ||
double | offset | ||
) |
Mark this joint as mimicking mimic using factor and offset.
Definition at line 171 of file joint_model.cpp.
void moveit::core::JointModel::setParentLinkModel | ( | const LinkModel * | link | ) | [inline] |
Definition at line 157 of file joint_model.h.
void moveit::core::JointModel::setPassive | ( | bool | flag | ) | [inline] |
Definition at line 402 of file joint_model.h.
void moveit::core::JointModel::setVariableBounds | ( | const std::string & | variable, |
const VariableBounds & | bounds | ||
) |
Set the lower and upper bounds for a variable. Throw an exception if the variable was not found.
Definition at line 118 of file joint_model.cpp.
void moveit::core::JointModel::setVariableBounds | ( | const std::vector< moveit_msgs::JointLimits > & | jlim | ) |
Override joint limits loaded from URDF. Unknown variables are ignored.
Definition at line 124 of file joint_model.cpp.
const LinkModel* moveit::core::JointModel::child_link_model_ [protected] |
The link after this joint.
Definition at line 459 of file joint_model.h.
std::vector<const JointModel*> moveit::core::JointModel::descendant_joint_models_ [protected] |
Pointers to all the joints that follow this one in the kinematic tree (including mimic joints)
Definition at line 477 of file joint_model.h.
std::vector<const LinkModel*> moveit::core::JointModel::descendant_link_models_ [protected] |
Pointers to all the links that will be moved if this joint changes value.
Definition at line 474 of file joint_model.h.
double moveit::core::JointModel::distance_factor_ [protected] |
The factor applied to the distance between two joint states.
Definition at line 486 of file joint_model.h.
int moveit::core::JointModel::first_variable_index_ [protected] |
The index of this joint's first variable, in the complete robot state.
Definition at line 489 of file joint_model.h.
int moveit::core::JointModel::joint_index_ [protected] |
Index for this joint in the array of joints of the complete model.
Definition at line 492 of file joint_model.h.
std::vector<std::string> moveit::core::JointModel::local_variable_names_ [protected] |
The local names to use for the variables that make up this joint.
Definition at line 442 of file joint_model.h.
const JointModel* moveit::core::JointModel::mimic_ [protected] |
The joint this one mimics (NULL for joints that do not mimic)
Definition at line 462 of file joint_model.h.
double moveit::core::JointModel::mimic_factor_ [protected] |
The offset to the mimic joint.
Definition at line 465 of file joint_model.h.
double moveit::core::JointModel::mimic_offset_ [protected] |
The multiplier to the mimic joint.
Definition at line 468 of file joint_model.h.
std::vector<const JointModel*> moveit::core::JointModel::mimic_requests_ [protected] |
The set of joints that should get a value copied to them when this joint changes.
Definition at line 471 of file joint_model.h.
std::string moveit::core::JointModel::name_ [protected] |
Name of the joint.
Definition at line 436 of file joint_model.h.
std::vector<const JointModel*> moveit::core::JointModel::non_fixed_descendant_joint_models_ [protected] |
Pointers to all the joints that follow this one in the kinematic tree, including mimic joints, but excluding fixed joints.
Definition at line 480 of file joint_model.h.
const LinkModel* moveit::core::JointModel::parent_link_model_ [protected] |
The link before this joint.
Definition at line 456 of file joint_model.h.
bool moveit::core::JointModel::passive_ [protected] |
Specify whether this joint is marked as passive in the SRDF.
Definition at line 483 of file joint_model.h.
JointType moveit::core::JointModel::type_ [protected] |
The type of joint.
Definition at line 439 of file joint_model.h.
Bounds moveit::core::JointModel::variable_bounds_ [protected] |
The bounds for each variable (low, high) in the same order as variable_names_.
Definition at line 448 of file joint_model.h.
std::vector<moveit_msgs::JointLimits> moveit::core::JointModel::variable_bounds_msg_ [protected] |
Definition at line 450 of file joint_model.h.
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within the JointModel only)
Definition at line 453 of file joint_model.h.
std::vector<std::string> moveit::core::JointModel::variable_names_ [protected] |
The full names to use for the variables that make up this joint.
Definition at line 445 of file joint_model.h.