38 #ifndef MOVEIT_CORE_ROBOT_MODEL_JOINT_MODEL_ 39 #define MOVEIT_CORE_ROBOT_MODEL_JOINT_MODEL_ 45 #include <moveit_msgs/JointLimits.h> 47 #include <Eigen/Geometry> 123 typedef std::vector<VariableBounds>
Bounds;
143 std::string getTypeName()
const;
150 return parent_link_model_;
156 return child_link_model_;
161 parent_link_model_ = link;
166 child_link_model_ = link;
178 return variable_names_;
186 return local_variable_names_;
192 return variable_index_map_.find(variable) != variable_index_map_.end();
198 return variable_names_.size();
204 return first_variable_index_;
210 first_variable_index_ = index;
222 joint_index_ = index;
226 int getLocalVariableIndex(
const std::string& variable)
const;
238 getVariableDefaultPositions(values, variable_bounds_);
244 virtual void getVariableDefaultPositions(
double* values,
const Bounds& other_bounds)
const = 0;
250 getVariableRandomPositions(rng, values, variable_bounds_);
256 const Bounds& other_bounds)
const = 0;
263 getVariableRandomPositionsNearBy(rng, values, variable_bounds_, near, distance);
269 const Bounds& other_bounds,
const double* near,
280 return satisfiesPositionBounds(values, variable_bounds_, margin);
285 virtual bool satisfiesPositionBounds(
const double* values,
const Bounds& other_bounds,
double margin)
const = 0;
292 return enforcePositionBounds(values, variable_bounds_);
298 virtual bool enforcePositionBounds(
double* values,
const Bounds& other_bounds)
const = 0;
303 return satisfiesVelocityBounds(values, variable_bounds_, margin);
307 virtual bool satisfiesVelocityBounds(
const double* values,
const Bounds& other_bounds,
double margin)
const;
312 return enforceVelocityBounds(values, variable_bounds_);
316 virtual bool enforceVelocityBounds(
double* values,
const Bounds& other_bounds)
const;
319 const VariableBounds& getVariableBounds(
const std::string& variable)
const;
324 return variable_bounds_;
328 void setVariableBounds(
const std::string& variable,
const VariableBounds& bounds);
331 void setVariableBounds(
const std::vector<moveit_msgs::JointLimits>& jlim);
336 return variable_bounds_msg_;
342 virtual double distance(
const double* value1,
const double* value2)
const = 0;
348 return distance_factor_;
355 distance_factor_ = factor;
359 virtual unsigned int getStateSpaceDimension()
const = 0;
370 return mimic_offset_;
376 return mimic_factor_;
380 void setMimic(
const JointModel* mimic,
double factor,
double offset);
385 return mimic_requests_;
389 void addMimicRequest(
const JointModel* joint);
390 void addDescendantJointModel(
const JointModel* joint);
391 void addDescendantLinkModel(
const LinkModel* link);
396 return descendant_link_models_;
402 return descendant_joint_models_;
408 return non_fixed_descendant_joint_models_;
426 virtual void interpolate(
const double* from,
const double* to,
const double t,
double* state)
const = 0;
429 virtual double getMaximumExtent(
const Bounds& other_bounds)
const = 0;
433 return getMaximumExtent(variable_bounds_);
440 virtual void computeTransform(
const double* joint_values, Eigen::Affine3d& transf)
const = 0;
443 virtual void computeVariablePositions(
const Eigen::Affine3d& transform,
double* joint_values)
const = 0;
448 void computeVariableBoundsMsg();
double getMimicFactor() const
If mimicking a joint, this is the multiplicative factor for that joint's value.
void setChildLinkModel(const LinkModel *link)
bool passive_
Specify whether this joint is marked as passive in the SRDF.
const std::string & getName() const
Get the name of the joint.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
JointType
The different types of joints we support.
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
const std::vector< const JointModel * > & getMimicRequests() const
The joint models whose values would be modified if the value of this joint changed.
std::string name_
Name of the joint.
void setJointIndex(int index)
Set the index of this joint within the robot model.
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...
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
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 JointModel * mimic_
The joint this one mimics (NULL for joints that do not mimic)
double getDistanceFactor() const
Get the factor that should be applied to the value returned by distance() when that value is used in ...
JointType type_
The type of joint.
bool hasVariable(const std::string &variable) const
Check if a particular variable is known to this joint.
std::map< std::string, VariableBounds > VariableBoundsMap
Data type for holding mappings from variable names to their bounds.
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
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.
double getMaximumExtent() const
double mimic_offset_
The multiplier to the mimic joint.
const std::vector< const JointModel * > & getDescendantJointModels() const
Get all the joint models that descend from this joint, in the kinematic tree.
int getJointIndex() const
Get the index of this joint within the robot model.
std::vector< const LinkModel * > descendant_link_models_
Pointers to all the links that will be moved if this joint changes value.
bool isPassive() const
Check if this joint is passive.
std::map< std::string, JointModel * > JointModelMap
Map of names to instances for JointModel.
double distance_factor_
The factor applied to the distance between two joint states.
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...
double getMimicOffset() const
If mimicking a joint, this is the offset added to that joint's value.
const Bounds & getVariableBounds() const
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()...
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...
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
void getVariableDefaultPositions(double *values) const
Provide a default value for the joint given the default joint variable bounds (maintained internally)...
std::map< std::string, int > VariableIndexMap
Data type for holding mappings from variable names to their position in a state vector.
double mimic_factor_
The offset to the mimic joint.
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
std::vector< const JointModel * > mimic_requests_
The set of joints that should get a value copied to them when this joint changes. ...
const LinkModel * parent_link_model_
The link before this 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 setFirstVariableIndex(int index)
Set the index of this joint's first variable within the full robot state.
const LinkModel * child_link_model_
The link after this joint.
int getFirstVariableIndex() const
Get the index of this joint's first variable within the full robot state.
const LinkModel * getChildLinkModel() const
Get the link that this joint connects to. There will always be such a link.
int joint_index_
Index for this joint in the array of joints of the complete model.
std::vector< moveit_msgs::JointLimits > variable_bounds_msg_
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
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.
A link from the robot. Contains the constant transform applied to the link and its geometry...
const std::vector< const LinkModel * > & getDescendantLinkModels() const
Get all the link models that descend from this joint, in the kinematic tree.
std::map< std::string, const JointModel * > JointModelMapConst
Map of names to const instances for JointModel.
std::vector< const JointModel * > descendant_joint_models_
Pointers to all the joints that follow this one in the kinematic tree (including mimic joints) ...
Main namespace for MoveIt!
bool acceleration_bounded_
void setParentLinkModel(const LinkModel *link)
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. ...
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
JointType getType() const
Get the type of joint.
double distance(const urdf::Pose &transform)
const std::vector< moveit_msgs::JointLimits > & getVariableBoundsMsg() const
Get the joint limits known to this model, as a message.
void setPassive(bool flag)
void setDistanceFactor(double factor)
Set the factor that should be applied to the value returned by distance() when that value is used in ...
int first_variable_index_
The index of this joint's first variable, in the complete robot state.
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...
const std::vector< const JointModel * > & getNonFixedDescendantJointModels() const
Get all the non-fixed joint models that descend from this joint, in the kinematic tree...
const JointModel * getMimic() const
Get the joint this one is mimicking.