Public Member Functions | Protected Attributes | Private Attributes | List of all members
moveit::core::RevoluteJointModel Class Reference

A revolute joint. More...

#include <revolute_joint_model.h>

Inheritance diagram for moveit::core::RevoluteJointModel:
Inheritance graph
[legend]

Public Member Functions

void computeTransform (const double *joint_values, Eigen::Isometry3d &transf) const override
 Given the joint values for a joint, compute the corresponding transform. The computed transform is guaranteed to be a valid isometry. More...
 
void computeVariablePositions (const Eigen::Isometry3d &transf, double *joint_values) const override
 Given the transform generated by joint, compute the corresponding joint values. Make sure the passed transform is a valid isometry. More...
 
double distance (const double *values1, const double *values2) const override
 Compute the distance between two joint states of the same model (represented by the variable values) More...
 
bool enforcePositionBounds (double *values, const Bounds &other_bounds) const override
 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. More...
 
const Eigen::Vector3dgetAxis () const
 Get the axis of rotation. More...
 
double getMaximumExtent (const Bounds &other_bounds) const override
 Get the extent of the state space (the maximum value distance() can ever report) More...
 
unsigned int getStateSpaceDimension () const override
 Get the dimension of the state space that corresponds to this joint. More...
 
void getVariableDefaultPositions (double *values, const Bounds &other_bounds) const override
 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. More...
 
void getVariableRandomPositions (random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const override
 Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated. More...
 
void getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *seed, const double distance) const override
 Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated. More...
 
bool harmonizePosition (double *values, const Bounds &other_bounds) const override
 
void interpolate (const double *from, const double *to, const double t, double *state) const override
 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. More...
 
bool isContinuous () const
 Check if this joint wraps around. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RevoluteJointModel (const std::string &name)
 
bool satisfiesPositionBounds (const double *values, const Bounds &other_bounds, double margin) const override
 Check if the set of position values for the variables of this joint are within bounds, up to some margin. More...
 
void setAxis (const Eigen::Vector3d &axis)
 Set the axis of rotation. More...
 
void setContinuous (bool flag)
 
- Public Member Functions inherited from moveit::core::JointModel
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. More...
 
const LinkModelgetChildLinkModel () const
 Get the link that this joint connects to. There will always be such a link. More...
 
const std::vector< const JointModel * > & getDescendantJointModels () const
 Get all the joint models that descend from this joint, in the kinematic tree. More...
 
const std::vector< const LinkModel * > & getDescendantLinkModels () const
 Get all the link models that descend from this joint, in the kinematic tree. More...
 
double getDistanceFactor () const
 Get the factor that should be applied to the value returned by distance() when that value is used in compound distances. More...
 
double getMaximumExtent () const
 
const JointModelgetMimic () const
 Get the joint this one is mimicking. More...
 
double getMimicFactor () const
 If mimicking a joint, this is the multiplicative factor for that joint's value. More...
 
double getMimicOffset () const
 If mimicking a joint, this is the offset added to that joint's value. More...
 
const std::vector< const JointModel * > & getMimicRequests () const
 The joint models whose values would be modified if the value of this joint changed. More...
 
const std::string & getName () const
 Get the name of the joint. More...
 
const std::vector< const JointModel * > & getNonFixedDescendantJointModels () const
 Get all the non-fixed joint models that descend from this joint, in the kinematic tree. More...
 
const LinkModelgetParentLinkModel () 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. More...
 
JointType getType () const
 Get the type of joint. More...
 
std::string getTypeName () const
 Get the type of joint as a string. More...
 
bool isPassive () const
 Check if this joint is passive. More...
 
 JointModel (const std::string &name)
 Construct a joint named name. More...
 
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. More...
 
void setMimic (const JointModel *mimic, double factor, double offset)
 Mark this joint as mimicking mimic using factor and offset. More...
 
void setParentLinkModel (const LinkModel *link)
 
void setPassive (bool flag)
 
virtual ~JointModel ()
 
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. More...
 
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. More...
 
bool hasVariable (const std::string &variable) const
 Check if a particular variable is known to this joint. More...
 
std::size_t getVariableCount () const
 Get the number of variables that describe this joint. More...
 
int getFirstVariableIndex () const
 Get the index of this joint's first variable within the full robot state. More...
 
void setFirstVariableIndex (int index)
 Set the index of this joint's first variable within the full robot state. More...
 
int getJointIndex () const
 Get the index of this joint within the robot model. More...
 
void setJointIndex (int index)
 Set the index of this joint within the robot model. More...
 
int getLocalVariableIndex (const std::string &variable) const
 Get the index of the variable within this joint. More...
 
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. More...
 
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. More...
 
void getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const double *seed, const double distance) const
 Provide random values for the joint variables (within default bounds). Enough memory is assumed to be allocated. More...
 
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. More...
 
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. More...
 
bool harmonizePosition (double *values) const
 
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. More...
 
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. More...
 
bool enforceVelocityBounds (double *values) const
 Force the specified velocities to be within bounds. Return true if changes were made. More...
 
virtual bool enforceVelocityBounds (double *values, const Bounds &other_bounds) const
 Force the specified velocities to be inside bounds. Return true if changes were made. More...
 
bool satisfiesAccelerationBounds (const double *values, double margin=0.0) const
 Check if the set of accelerations for the variables of this joint are within bounds. More...
 
virtual bool satisfiesAccelerationBounds (const double *values, const Bounds &other_bounds, double margin) const
 Check if the set of accelerations for the variables of this joint are within bounds, up to some margin. More...
 
const VariableBoundsgetVariableBounds (const std::string &variable) const
 Get the bounds for a variable. Throw an exception if the variable was not found. More...
 
const BoundsgetVariableBounds () const
 Get the variable bounds for this joint, in the same order as the names returned by getVariableNames() More...
 
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. More...
 
void setVariableBounds (const std::vector< moveit_msgs::JointLimits > &jlim)
 Override joint limits loaded from URDF. Unknown variables are ignored. More...
 
const std::vector< moveit_msgs::JointLimits > & getVariableBoundsMsg () const
 Get the joint limits known to this model, as a message. More...
 

Protected Attributes

Eigen::Vector3d axis_
 The axis of the joint. More...
 
bool continuous_
 Flag indicating whether this joint wraps around. More...
 
- Protected Attributes inherited from moveit::core::JointModel
const LinkModelchild_link_model_
 The link after this joint. More...
 
std::vector< const JointModel * > descendant_joint_models_
 Pointers to all the joints that follow this one in the kinematic tree (including mimic joints) More...
 
std::vector< const LinkModel * > descendant_link_models_
 Pointers to all the links that will be moved if this joint changes value. More...
 
double distance_factor_
 The factor applied to the distance between two joint states. More...
 
int first_variable_index_
 The index of this joint's first variable, in the complete robot state. More...
 
int joint_index_
 Index for this joint in the array of joints of the complete model. More...
 
std::vector< std::string > local_variable_names_
 The local names to use for the variables that make up this joint. More...
 
const JointModelmimic_
 The joint this one mimics (NULL for joints that do not mimic) More...
 
double mimic_factor_
 The offset to the mimic joint. More...
 
double mimic_offset_
 The multiplier to the mimic joint. More...
 
std::vector< const JointModel * > mimic_requests_
 The set of joints that should get a value copied to them when this joint changes. More...
 
std::string name_
 Name of the joint. More...
 
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. More...
 
const LinkModelparent_link_model_
 The link before this joint. More...
 
bool passive_
 Specify whether this joint is marked as passive in the SRDF. More...
 
JointType type_
 The type of joint. More...
 
Bounds variable_bounds_
 The bounds for each variable (low, high) in the same order as variable_names_. More...
 
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) More...
 
std::vector< std::string > variable_names_
 The full names to use for the variables that make up this joint. More...
 

Private Attributes

double x2_
 
double xy_
 
double xz_
 
double y2_
 
double yz_
 
double z2_
 

Additional Inherited Members

- Public Types inherited from moveit::core::JointModel
using Bounds = std::vector< VariableBounds >
 The datatype for the joint bounds. More...
 
enum  JointType {
  UNKNOWN, REVOLUTE, PRISMATIC, PLANAR,
  FLOATING, FIXED
}
 The different types of joints we support. More...
 
- Protected Member Functions inherited from moveit::core::JointModel
void computeVariableBoundsMsg ()
 

Detailed Description

A revolute joint.

Definition at line 110 of file revolute_joint_model.h.

Constructor & Destructor Documentation

◆ RevoluteJointModel()

moveit::core::RevoluteJointModel::RevoluteJointModel ( const std::string &  name)

Definition at line 114 of file revolute_joint_model.cpp.

Member Function Documentation

◆ computeTransform()

void moveit::core::RevoluteJointModel::computeTransform ( const double *  joint_values,
Eigen::Isometry3d &  transf 
) const
overridevirtual

Given the joint values for a joint, compute the corresponding transform. The computed transform is guaranteed to be a valid isometry.

Implements moveit::core::JointModel.

Definition at line 288 of file revolute_joint_model.cpp.

◆ computeVariablePositions()

void moveit::core::RevoluteJointModel::computeVariablePositions ( const Eigen::Isometry3d &  transform,
double *  joint_values 
) const
overridevirtual

Given the transform generated by joint, compute the corresponding joint values. Make sure the passed transform is a valid isometry.

Implements moveit::core::JointModel.

Definition at line 327 of file revolute_joint_model.cpp.

◆ distance()

double moveit::core::RevoluteJointModel::distance ( const double *  value1,
const double *  value2 
) const
overridevirtual

Compute the distance between two joint states of the same model (represented by the variable values)

Implements moveit::core::JointModel.

Definition at line 216 of file revolute_joint_model.cpp.

◆ enforcePositionBounds()

bool moveit::core::RevoluteJointModel::enforcePositionBounds ( double *  values,
const Bounds other_bounds 
) const
overridevirtual

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.

Implements moveit::core::JointModel.

Definition at line 257 of file revolute_joint_model.cpp.

◆ getAxis()

const Eigen::Vector3d& moveit::core::RevoluteJointModel::getAxis ( ) const
inline

Get the axis of rotation.

Definition at line 175 of file revolute_joint_model.h.

◆ getMaximumExtent()

double moveit::core::RevoluteJointModel::getMaximumExtent ( const Bounds other_bounds) const
overridevirtual

Get the extent of the state space (the maximum value distance() can ever report)

Implements moveit::core::JointModel.

Definition at line 157 of file revolute_joint_model.cpp.

◆ getStateSpaceDimension()

unsigned int moveit::core::RevoluteJointModel::getStateSpaceDimension ( ) const
overridevirtual

Get the dimension of the state space that corresponds to this joint.

Implements moveit::core::JointModel.

Definition at line 127 of file revolute_joint_model.cpp.

◆ getVariableDefaultPositions()

void moveit::core::RevoluteJointModel::getVariableDefaultPositions ( double *  values,
const Bounds other_bounds 
) const
overridevirtual

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.

Implements moveit::core::JointModel.

Definition at line 162 of file revolute_joint_model.cpp.

◆ getVariableRandomPositions()

void moveit::core::RevoluteJointModel::getVariableRandomPositions ( random_numbers::RandomNumberGenerator rng,
double *  values,
const Bounds other_bounds 
) const
overridevirtual

Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.

Implements moveit::core::JointModel.

Definition at line 171 of file revolute_joint_model.cpp.

◆ getVariableRandomPositionsNearBy()

void moveit::core::RevoluteJointModel::getVariableRandomPositionsNearBy ( random_numbers::RandomNumberGenerator rng,
double *  values,
const Bounds other_bounds,
const double *  seed,
const double  distance 
) const
overridevirtual

Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated.

Implements moveit::core::JointModel.

Definition at line 177 of file revolute_joint_model.cpp.

◆ harmonizePosition()

bool moveit::core::RevoluteJointModel::harmonizePosition ( double *  values,
const Bounds other_bounds 
) const
overridevirtual

Harmonize position of revolute joints, adding/subtracting multiples of 2*Pi to bring them back into bounds. Return true if changes were made.

Reimplemented from moveit::core::JointModel.

Definition at line 235 of file revolute_joint_model.cpp.

◆ interpolate()

void moveit::core::RevoluteJointModel::interpolate ( const double *  from,
const double *  to,
const double  t,
double *  state 
) const
overridevirtual

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.

Implements moveit::core::JointModel.

Definition at line 191 of file revolute_joint_model.cpp.

◆ isContinuous()

bool moveit::core::RevoluteJointModel::isContinuous ( ) const
inline

Check if this joint wraps around.

Definition at line 169 of file revolute_joint_model.h.

◆ satisfiesPositionBounds()

bool moveit::core::RevoluteJointModel::satisfiesPositionBounds ( const double *  values,
const Bounds other_bounds,
double  margin 
) const
overridevirtual

Check if the set of position values for the variables of this joint are within bounds, up to some margin.

Implements moveit::core::JointModel.

Definition at line 227 of file revolute_joint_model.cpp.

◆ setAxis()

void moveit::core::RevoluteJointModel::setAxis ( const Eigen::Vector3d axis)

Set the axis of rotation.

Definition at line 132 of file revolute_joint_model.cpp.

◆ setContinuous()

void moveit::core::RevoluteJointModel::setContinuous ( bool  flag)

Definition at line 143 of file revolute_joint_model.cpp.

Member Data Documentation

◆ axis_

Eigen::Vector3d moveit::core::RevoluteJointModel::axis_
protected

The axis of the joint.

Definition at line 185 of file revolute_joint_model.h.

◆ continuous_

bool moveit::core::RevoluteJointModel::continuous_
protected

Flag indicating whether this joint wraps around.

Definition at line 188 of file revolute_joint_model.h.

◆ x2_

double moveit::core::RevoluteJointModel::x2_
private

Definition at line 191 of file revolute_joint_model.h.

◆ xy_

double moveit::core::RevoluteJointModel::xy_
private

Definition at line 191 of file revolute_joint_model.h.

◆ xz_

double moveit::core::RevoluteJointModel::xz_
private

Definition at line 191 of file revolute_joint_model.h.

◆ y2_

double moveit::core::RevoluteJointModel::y2_
private

Definition at line 191 of file revolute_joint_model.h.

◆ yz_

double moveit::core::RevoluteJointModel::yz_
private

Definition at line 191 of file revolute_joint_model.h.

◆ z2_

double moveit::core::RevoluteJointModel::z2_
private

Definition at line 191 of file revolute_joint_model.h.


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


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Apr 18 2024 02:23:41