#include <planar_joint_model.h>
Public Types | |
enum | MotionModel { HOLONOMIC, DIFF_DRIVE } |
different types of planar joints we support More... | |
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... | |
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... | |
double | getAngularDistanceWeight () const |
double | getMaximumExtent (const Bounds &other_bounds) const override |
Get the extent of the state space (the maximum value distance() can ever report) More... | |
double | getMinTranslationalDistance () const |
MotionModel | getMotionModel () const |
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... | |
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 | normalizeRotation (double *values) const |
PlanarJointModel (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 | setAngularDistanceWeight (double weight) |
void | setMinTranslationalDistance (double min_translational_distance) |
void | setMotionModel (MotionModel model) |
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 LinkModel * | getChildLinkModel () 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 JointModel * | getMimic () 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 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. 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... | |
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. 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 VariableBounds & | getVariableBounds (const std::string &variable) const |
Get the bounds for a variable. Throw an exception if the variable was not found. More... | |
const Bounds & | getVariableBounds () 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... | |
Private Attributes | |
double | angular_distance_weight_ |
double | min_translational_distance_ |
Only used for the differential drive motion model. More... | |
MotionModel | motion_model_ |
Additional Inherited Members | |
Protected Member Functions inherited from moveit::core::JointModel | |
void | computeVariableBoundsMsg () |
Protected Attributes inherited from moveit::core::JointModel | |
const LinkModel * | child_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 JointModel * | mimic_ |
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 LinkModel * | parent_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... | |
A planar joint.
Definition at line 110 of file planar_joint_model.h.
different types of planar joints we support
Enumerator | |
---|---|
HOLONOMIC | |
DIFF_DRIVE |
Definition at line 146 of file planar_joint_model.h.
moveit::core::PlanarJointModel::PlanarJointModel | ( | const std::string & | name | ) |
Definition at line 115 of file planar_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 393 of file planar_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 399 of file planar_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 332 of file planar_joint_model.cpp.
|
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 374 of file planar_joint_model.cpp.
|
inline |
Definition at line 171 of file planar_joint_model.h.
|
overridevirtual |
Get the extent of the state space (the maximum value distance() can ever report)
Implements moveit::core::JointModel.
Definition at line 149 of file planar_joint_model.cpp.
|
inline |
Definition at line 181 of file planar_joint_model.h.
|
inline |
Definition at line 191 of file planar_joint_model.h.
|
overridevirtual |
Get the dimension of the state space that corresponds to this joint.
Implements moveit::core::JointModel.
Definition at line 144 of file planar_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 156 of file planar_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 169 of file planar_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 185 of file planar_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 246 of file planar_joint_model.cpp.
bool moveit::core::PlanarJointModel::normalizeRotation | ( | double * | values | ) | const |
Make the yaw component of a state's value vector be in the range [-Pi, Pi]. enforceBounds() also calls this function; Return true if a change is actually made
Definition at line 361 of file planar_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 353 of file planar_joint_model.cpp.
|
inline |
Definition at line 176 of file planar_joint_model.h.
|
inline |
Definition at line 186 of file planar_joint_model.h.
|
inline |
Definition at line 196 of file planar_joint_model.h.
|
private |
Definition at line 207 of file planar_joint_model.h.
|
private |
Only used for the differential drive motion model.
Definition at line 210 of file planar_joint_model.h.
|
private |
Definition at line 208 of file planar_joint_model.h.