50 , parent_link_model_(nullptr)
51 , child_link_model_(nullptr)
56 , distance_factor_(1.0)
57 , first_variable_index_(-1)
89 throw Exception(
"Could not find variable '" + variable +
"' to get bounds for within joint '" +
name_ +
"'");
96 for (std::size_t i = 0; i < other_bounds.size(); ++i)
97 if (other_bounds[i].max_velocity_ < values[i])
99 values[i] = other_bounds[i].max_velocity_;
102 else if (other_bounds[i].min_velocity_ > values[i])
104 values[i] = other_bounds[i].min_velocity_;
112 for (std::size_t i = 0; i < other_bounds.size(); ++i)
113 if (other_bounds[i].max_velocity_ + margin < values[i])
115 else if (other_bounds[i].min_velocity_ - margin > values[i])
134 for (std::size_t i = 0; i < jlim.size(); ++i)
138 if (jlim[i].has_position_limits)
144 if (jlim[i].has_velocity_limits)
149 variable_bounds_[j].acceleration_bounded_ = jlim[i].has_acceleration_limits;
150 if (jlim[i].has_acceleration_limits)
165 moveit_msgs::JointLimits lim;
173 lim.max_acceleration =
205 inline void printBoundHelper(std::ostream& out,
double v)
207 if (v <= -std::numeric_limits<double>::infinity())
209 else if (v >= std::numeric_limits<double>::infinity())
JointModel(const std::string &name)
Construct a joint named name.
void setMimic(const JointModel *mimic, double factor, double offset)
Mark this joint as mimicking mimic using factor and offset.
std::string name_
Name of the 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...
void addDescendantJointModel(const JointModel *joint)
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
const JointModel * mimic_
The joint this one mimics (NULL for joints that do not mimic)
JointType type_
The type of joint.
bool enforceVelocityBounds(double *values) const
Force the specified velocities to be within bounds. Return true if changes were made.
int getLocalVariableIndex(const std::string &variable) const
Get the index of the variable within this joint.
double mimic_offset_
The multiplier to the mimic joint.
std::vector< const LinkModel * > descendant_link_models_
Pointers to all the links that will be moved if this joint changes value.
void computeVariableBoundsMsg()
void addMimicRequest(const JointModel *joint)
Notify this joint that there is another joint that mimics it.
This may be thrown if unrecoverable errors occur.
const Bounds & getVariableBounds() const
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()...
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
void addDescendantLinkModel(const LinkModel *link)
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. ...
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.
A link from the robot. Contains the constant transform applied to the link and its geometry...
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_
std::string getTypeName() const
Get the type of joint as a string.
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.
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.