moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
A fixed joint. More...
#include <fixed_joint_model.h>
Public Member Functions | |
FixedJointModel (const std::string &name, size_t joint_index, size_t first_variable_index) | |
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. | |
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. | |
void | getVariableRandomPositionsNearBy (random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const override |
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to be allocated. | |
bool | enforcePositionBounds (double *values, const Bounds &other_bounds) const override |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous revolute joints are made between -Pi and Pi. Return true if changes were made. | |
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. | |
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. | |
unsigned int | getStateSpaceDimension () const override |
Get the dimension of the state space that corresponds to this joint. | |
double | getMaximumExtent (const Bounds &other_bounds) const override |
Get the extent of the state space (the maximum value distance() can ever report) | |
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) | |
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. | |
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. | |
Public Member Functions inherited from moveit::core::JointModel | |
JointModel (const std::string &name, size_t joint_index, size_t first_variable_index) | |
Constructs a joint named name. | |
virtual | ~JointModel () |
const std::string & | getName () const |
Get the name of the joint. | |
JointType | getType () const |
Get the type of joint. | |
std::string | getTypeName () const |
Get the type of joint as a string. | |
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 nullptr here. | |
const LinkModel * | getChildLinkModel () const |
Get the link that this joint connects to. There will always be such a link. | |
void | setParentLinkModel (const LinkModel *link) |
void | setChildLinkModel (const LinkModel *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. | |
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. | |
const JointModel * | getMimic () const |
Get the joint this one is mimicking. | |
double | getMimicOffset () const |
If mimicking a joint, this is the offset added to that joint's value. | |
double | getMimicFactor () const |
If mimicking a joint, this is the multiplicative factor for that joint's value. | |
void | setMimic (const JointModel *mimic, double factor, double offset) |
Mark this joint as mimicking mimic using factor and offset. | |
const std::vector< const JointModel * > & | getMimicRequests () const |
The joint models whose values would be modified if the value of this joint changed. | |
void | addMimicRequest (const JointModel *joint) |
Notify this joint that there is another joint that mimics it. | |
void | addDescendantJointModel (const JointModel *joint) |
void | addDescendantLinkModel (const LinkModel *link) |
const std::vector< const LinkModel * > & | getDescendantLinkModels () const |
Get all the link models that descend from this joint, in the kinematic tree. | |
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 JointModel * > & | getNonFixedDescendantJointModels () const |
Get all the non-fixed joint models that descend from this joint, in the kinematic tree. | |
bool | isPassive () const |
Check if this joint is passive. | |
void | setPassive (bool flag) |
double | getMaximumExtent () const |
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. | |
size_t | getFirstVariableIndex () const |
Get the index of this joint's first variable within the full robot state. | |
size_t | getJointIndex () const |
Get the index of this joint within the robot model. | |
size_t | getLocalVariableIndex (const std::string &variable) const |
Get the index of the variable within this joint. | |
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. | |
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. | |
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. | |
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. | |
bool | enforcePositionBounds (double *values) const |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous revolute joints are made between -Pi and Pi. Returns true if changes were made. | |
virtual bool | harmonizePosition (double *values, const Bounds &other_bounds) const |
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. | |
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. | |
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. | |
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. | |
bool | satisfiesJerkBounds (const double *values, double margin=0.0) const |
Check if the set of jerks for the variables of this joint are within bounds. | |
virtual bool | satisfiesJerkBounds (const double *values, const Bounds &other_bounds, double margin) const |
Check if the set of jerks for the variables of this joint are within bounds, up to some margin. | |
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::msg::JointLimits > &jlim) |
Override joint limits loaded from URDF. Unknown variables are ignored. | |
const std::vector< moveit_msgs::msg::JointLimits > & | getVariableBoundsMsg () const |
Get the joint limits known to this model, as a message. | |
Additional Inherited Members | |
Public Types inherited from moveit::core::JointModel | |
enum | JointType { UNKNOWN , REVOLUTE , PRISMATIC , PLANAR , FLOATING , FIXED } |
The different types of joints we support. More... | |
using | Bounds = std::vector< VariableBounds > |
The datatype for the joint bounds. | |
Protected Member Functions inherited from moveit::core::JointModel | |
void | computeVariableBoundsMsg () |
Protected Attributes inherited from moveit::core::JointModel | |
JointType | type_ |
The type of joint. | |
std::vector< std::string > | local_variable_names_ |
The local names to use for the variables that make up this joint. | |
std::vector< std::string > | variable_names_ |
The full names to use for the variables that make up this joint. | |
Bounds | variable_bounds_ |
The bounds for each variable (low, high) in the same order as variable_names_. | |
std::vector< moveit_msgs::msg::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) | |
const LinkModel * | parent_link_model_ |
The link before this joint. | |
const LinkModel * | child_link_model_ |
The link after this joint. | |
const JointModel * | mimic_ |
The joint this one mimics (nullptr for joints that do not mimic) | |
double | mimic_factor_ |
The multiplier to the mimic joint. | |
double | mimic_offset_ |
The offset 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::vector< const LinkModel * > | descendant_link_models_ |
Pointers to all the links that will be moved if this joint changes value. | |
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 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. | |
bool | passive_ |
Specify whether this joint is marked as passive in the SRDF. | |
double | distance_factor_ |
The factor applied to the distance between two joint states. | |
A fixed joint.
Definition at line 46 of file fixed_joint_model.h.
moveit::core::FixedJointModel::FixedJointModel | ( | const std::string & | name, |
size_t | joint_index, | ||
size_t | first_variable_index | ||
) |
Definition at line 43 of file fixed_joint_model.cpp.
|
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 95 of file fixed_joint_model.cpp.
|
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 100 of file fixed_joint_model.cpp.
|
overridevirtual |
Compute the distance between two joint states of the same model (represented by the variable values)
Implements moveit::core::JointModel.
Definition at line 80 of file fixed_joint_model.cpp.
|
overridevirtual |
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous revolute joints are made between -Pi and Pi. Return true if changes were made.
Implements moveit::core::JointModel.
Definition at line 69 of file fixed_joint_model.cpp.
|
overridevirtual |
Get the extent of the state space (the maximum value distance() can ever report)
Implements moveit::core::JointModel.
Definition at line 85 of file fixed_joint_model.cpp.
|
overridevirtual |
Get the dimension of the state space that corresponds to this joint.
Implements moveit::core::JointModel.
Definition at line 49 of file fixed_joint_model.cpp.
|
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 54 of file fixed_joint_model.cpp.
|
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 58 of file fixed_joint_model.cpp.
|
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 63 of file fixed_joint_model.cpp.
|
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 90 of file fixed_joint_model.cpp.
|
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 74 of file fixed_joint_model.cpp.