49 , joint_index_(joint_index)
50 , first_variable_index_(first_variable_index)
52 , parent_link_model_(nullptr)
53 , child_link_model_(nullptr)
58 , distance_factor_(1.0)
89 throw Exception(
"Could not find variable '" + variable +
"' to get bounds for within joint '" + name_ +
"'");
101 for (std::size_t i = 0; i < other_bounds.size(); ++i)
102 if (other_bounds[i].max_velocity_ < values[i])
104 values[i] = other_bounds[i].max_velocity_;
107 else if (other_bounds[i].min_velocity_ > values[i])
109 values[i] = other_bounds[i].min_velocity_;
117 for (std::size_t i = 0; i < other_bounds.size(); ++i)
118 if (other_bounds[i].max_velocity_ + margin < values[i])
120 else if (other_bounds[i].min_velocity_ - margin > values[i])
139 for (
const moveit_msgs::msg::JointLimits& joint_limit : jlim)
143 if (joint_limit.has_position_limits)
149 if (joint_limit.has_velocity_limits)
154 variable_bounds_[j].acceleration_bounded_ = joint_limit.has_acceleration_limits;
155 if (joint_limit.has_acceleration_limits)
161 if (joint_limit.has_jerk_limits)
176 moveit_msgs::msg::JointLimits lim;
184 lim.max_acceleration =
218 inline void printBoundHelper(std::ostream& out,
double v)
220 if (v <= -std::numeric_limits<double>::infinity())
222 else if (v >= std::numeric_limits<double>::infinity())
246 <<
"J." << (b.
jerk_bounded_ ?
"bounded" :
"unbounded") <<
" [";
This may be thrown if unrecoverable errors occur.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
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.
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
size_t getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
const JointModel * mimic_
The joint this one mimics (nullptr for joints that do not mimic)
JointType type_
The type of 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.
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.
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()
JointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
Constructs a joint named name.
virtual bool harmonizePosition(double *values, const Bounds &other_bounds) const
std::vector< moveit_msgs::msg::JointLimits > variable_bounds_msg_
void addDescendantJointModel(const JointModel *joint)
void setMimic(const JointModel *mimic, double factor, double offset)
Mark this joint as mimicking mimic using factor and offset.
void computeVariableBoundsMsg()
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
std::vector< const LinkModel * > descendant_link_models_
Pointers to all the links that will be moved if this joint changes value.
JointType getType() const
Get the type of joint.
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.
A link from the robot. Contains the constant transform applied to the link and its geometry.
std::ostream & operator<<(std::ostream &out, const VariableBounds &b)
Operator overload for printing variable bounds to a stream.
Main namespace for MoveIt.
bool acceleration_bounded_