44 #include <moveit_msgs/msg/joint_limits.hpp>
45 #include <random_numbers/random_numbers.h>
46 #include <Eigen/Geometry>
131 using Bounds = std::vector<VariableBounds>;
140 JointModel(
const std::string&
name,
size_t joint_index,
size_t first_variable_index);
218 return first_variable_index_;
258 const Bounds& other_bounds)
const = 0;
271 const Bounds& other_bounds,
const double* near,
352 virtual double distance(
const double* value1,
const double* value2)
const = 0;
436 virtual void interpolate(
const double* from,
const double* to,
const double t,
double* state)
const = 0;
451 virtual void computeTransform(
const double* joint_values, Eigen::Isometry3d& transf)
const = 0;
467 size_t first_variable_index_;
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a 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 sta...
void addMimicRequest(const JointModel *joint)
Notify this joint that there is another joint that mimics it.
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.
double getDistanceFactor() const
Get the factor that should be applied to the value returned by distance() when that value is used in ...
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
double getMimicFactor() const
If mimicking a joint, this is the multiplicative factor for that joint's value.
size_t getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
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...
const JointModel * mimic_
The joint this one mimics (nullptr for joints that do not mimic)
virtual void computeVariablePositions(const Eigen::Isometry3d &transform, double *joint_values) const =0
Given the transform generated by joint, compute the corresponding joint values. Make sure the passed ...
void setChildLinkModel(const LinkModel *link)
JointType type_
The type of joint.
size_t getJointIndex() const
Get the index of this joint within the robot model.
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
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 ...
virtual unsigned int getStateSpaceDimension() const =0
Get the dimension of the state space that corresponds to this joint.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
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.
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< VariableBounds > Bounds
The datatype for the joint bounds.
virtual bool enforcePositionBounds(double *values, const Bounds &other_bounds) const =0
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
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.
void setDistanceFactor(double factor)
Set the factor that should be applied to the value returned by distance() when that value is used in ...
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 ...
double mimic_factor_
The multiplier to the mimic 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,...
const Bounds & getVariableBounds() const
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()
JointType
The different types of joints we support.
const std::vector< moveit_msgs::msg::JointLimits > & getVariableBoundsMsg() const
Get the joint limits known to this model, as a message.
JointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
Constructs a joint named name.
size_t getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) const
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....
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...
void getVariableDefaultPositions(double *values) const
Provide a default value for the joint given the default joint variable bounds (maintained internally)...
std::vector< moveit_msgs::msg::JointLimits > variable_bounds_msg_
bool hasVariable(const std::string &variable) const
Check if a particular variable is known to this joint.
bool passive_
Specify whether this joint is marked as passive in the SRDF.
const LinkModel * parent_link_model_
The link before this joint.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
void addDescendantJointModel(const JointModel *joint)
const std::string & getName() const
Get the name of the joint.
double getMimicOffset() const
If mimicking a joint, this is the offset added to that joint's value.
void setParentLinkModel(const LinkModel *link)
void setMimic(const JointModel *mimic, double factor, double offset)
Mark this joint as mimicking mimic using factor and offset.
const std::vector< const LinkModel * > & getDescendantLinkModels() const
Get all the link models that descend from this joint, in the kinematic tree.
void computeVariableBoundsMsg()
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)
virtual double getMaximumExtent(const Bounds &other_bounds) const =0
Get the extent of the state space (the maximum value distance() can ever report)
bool isPassive() const
Check if this joint is passive.
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
double distance_factor_
The factor applied to the distance between two joint states.
virtual void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const =0
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
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.
const std::vector< const JointModel * > & getDescendantJointModels() const
Get all the joint models that descend from this joint, in the kinematic tree.
double getMaximumExtent() const
bool harmonizePosition(double *values) const
const std::vector< const JointModel * > & getMimicRequests() const
The joint models whose values would be modified if the value of this joint changed.
std::vector< const LinkModel * > descendant_link_models_
Pointers to all the links that will be moved if this joint changes value.
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...
JointType getType() const
Get the type of joint.
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,...
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 defau...
void setPassive(bool flag)
const JointModel * getMimic() const
Get the joint this one is mimicking.
const std::vector< const JointModel * > & getNonFixedDescendantJointModels() const
Get all the non-fixed joint models that descend from this joint, in the kinematic tree.
std::string getTypeName() const
Get the type of joint as a string.
void addDescendantLinkModel(const LinkModel *link)
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
const LinkModel * child_link_model_
The link after this joint.
A link from the robot. Contains the constant transform applied to the link and its geometry.
std::map< std::string, VariableBounds > VariableBoundsMap
Data type for holding mappings from variable names to their bounds.
std::map< std::string, size_t > VariableIndexMap
Data type for holding mappings from variable names to their position in a state vector.
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
std::map< std::string, const JointModel * > JointModelMapConst
Map of names to const instances for JointModel.
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
Main namespace for MoveIt.
bool acceleration_bounded_