Go to the documentation of this file.
44 #include <moveit_msgs/JointLimits.h>
46 #include <Eigen/Geometry>
122 using Bounds = std::vector<VariableBounds>;
130 const std::string&
getName()
const
189 bool hasVariable(
const std::string& variable)
const
268 const Bounds& other_bounds,
const double* seed,
344 void setVariableBounds(
const std::string& variable,
const VariableBounds& bounds);
358 virtual double distance(
const double* value1,
const double* value2)
const = 0;
442 virtual void interpolate(
const double* from,
const double* to,
const double t,
double* state)
const = 0;
457 virtual void computeTransform(
const double* joint_values, Eigen::Isometry3d& transf)
const = 0;
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::vector< const JointModel * > & getNonFixedDescendantJointModels() const
Get all the non-fixed joint models that descend from this joint, in the kinematic tree.
double distance_factor_
The factor applied to the distance between two joint states.
std::map< std::string, VariableBounds > VariableBoundsMap
Data type for holding mappings from variable names to their bounds.
bool enforcePositionBounds(double *values) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
std::vector< const LinkModel * > descendant_link_models_
Pointers to all the links that will be moved if this joint changes value.
const Bounds & getVariableBounds() const
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()
int getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
const std::vector< moveit_msgs::JointLimits > & getVariableBoundsMsg() const
Get the joint limits known to this model, as a message.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
void computeVariableBoundsMsg()
double getMimicOffset() const
If mimicking a joint, this is the offset added to that joint's value.
const LinkModel * parent_link_model_
The link before this joint.
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
void getVariableDefaultPositions(double *values) const
Provide a default value for the joint given the default joint variable bounds (maintained internally)...
double getDistanceFactor() const
Get the factor that should be applied to the value returned by distance() when that value is used in ...
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...
const std::vector< const LinkModel * > & getDescendantLinkModels() const
Get all the link models that descend from this joint, in the kinematic tree.
int joint_index_
Index for this joint in the array of joints of the complete model.
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 setFirstVariableIndex(int index)
Set the index of this joint's first variable within the full robot state.
std::map< std::string, int > VariableIndexMap
Data type for holding mappings from variable names to their position in a state vector.
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
bool hasVariable(const std::string &variable) const
Check if a particular variable is known to this joint.
const std::string & getName() const
Get the name of the joint.
double getMimicFactor() const
If mimicking a joint, this is the multiplicative factor for that joint's value.
int first_variable_index_
The index of this joint's first variable, in the complete robot state.
void addDescendantLinkModel(const LinkModel *link)
bool passive_
Specify whether this joint is marked as passive in the SRDF.
std::vector< const JointModel * > descendant_joint_models_
Pointers to all the joints that follow this one in the kinematic tree (including mimic joints)
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.
JointType getType() const
Get the type of joint.
void setParentLinkModel(const LinkModel *link)
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
const LinkModel * getParentLinkModel() const
Get the link that this joint connects to. The robot is assumed to start with a joint,...
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
double getMaximumExtent() const
void setMimic(const JointModel *mimic, double factor, double offset)
Mark this joint as mimicking mimic using factor and offset.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
void setPassive(bool flag)
int getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
const std::vector< const JointModel * > & getMimicRequests() const
The joint models whose values would be modified if the value of this joint changed.
void setChildLinkModel(const LinkModel *link)
std::vector< moveit_msgs::JointLimits > variable_bounds_msg_
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
virtual unsigned int getStateSpaceDimension() const =0
Get the dimension of the state space that corresponds to this joint.
int getJointIndex() const
Get the index of this joint within the robot model.
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.
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...
JointType
The different types of joints we support.
void setDistanceFactor(double factor)
Set the factor that should be applied to the value returned by distance() when that value is used in ...
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) const
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...
Main namespace for MoveIt.
std::vector< double > values
JointModel(const std::string &name)
Construct a joint named name.
std::string getTypeName() const
Get the type of joint as a string.
const JointModel * getMimic() const
Get the joint this one is mimicking.
const JointModel * mimic_
The joint this one mimics (NULL for joints that do not mimic)
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::string name_
Name of the joint.
double mimic_offset_
The multiplier to the mimic joint.
bool acceleration_bounded_
std::map< std::string, const JointModel * > JointModelMapConst
Map of names to const instances for JointModel.
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)
void addDescendantJointModel(const JointModel *joint)
double mimic_factor_
The offset to the mimic joint.
void addMimicRequest(const JointModel *joint)
Notify this joint that there is another joint that mimics it.
const std::vector< const JointModel * > & getDescendantJointModels() const
Get all the joint models that descend from this joint, in the kinematic tree.
std::vector< const JointModel * > mimic_requests_
The set of joints that should get a value copied to them when this joint changes.
void setJointIndex(int index)
Set the index of this joint within the robot model.
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...
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.
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 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 ...
bool isPassive() const
Check if this joint is passive.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
const LinkModel * child_link_model_
The link after this 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 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...
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14