moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
joint_model.cpp
Go to the documentation of this file.
1/*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2013, Ioan A. Sucan
5 * Copyright (c) 2008-2013, Willow Garage, Inc.
6 * All rights reserved.
7 *
8 * Redistribution and use in source and binary forms, with or without
9 * modification, are permitted provided that the following conditions
10 * are met:
11 *
12 * * Redistributions of source code must retain the above copyright
13 * notice, this list of conditions and the following disclaimer.
14 * * Redistributions in binary form must reproduce the above
15 * copyright notice, this list of conditions and the following
16 * disclaimer in the documentation and/or other materials provided
17 * with the distribution.
18 * * Neither the name of the Willow Garage nor the names of its
19 * contributors may be used to endorse or promote products derived
20 * from this software without specific prior written permission.
21 *
22 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 * POSSIBILITY OF SUCH DAMAGE.
34 *********************************************************************/
35
36/* Author: Ioan Sucan */
37
41#include <algorithm>
42
43namespace moveit
44{
45namespace core
46{
47JointModel::JointModel(const std::string& name, size_t joint_index, size_t first_variable_index)
48 : name_(name)
49 , joint_index_(joint_index)
50 , first_variable_index_(first_variable_index)
51 , type_(UNKNOWN)
52 , parent_link_model_(nullptr)
53 , child_link_model_(nullptr)
54 , mimic_(nullptr)
55 , mimic_factor_(1.0)
56 , mimic_offset_(0.0)
57 , passive_(false)
58 , distance_factor_(1.0)
59{
60}
61
62JointModel::~JointModel() = default;
63
64std::string JointModel::getTypeName() const
65{
66 switch (type_)
67 {
68 case UNKNOWN:
69 return "Unknown";
70 case REVOLUTE:
71 return "Revolute";
72 case PRISMATIC:
73 return "Prismatic";
74 case PLANAR:
75 return "Planar";
76 case FLOATING:
77 return "Floating";
78 case FIXED:
79 return "Fixed";
80 default:
81 return "[Unknown]";
82 }
83}
84
85size_t JointModel::getLocalVariableIndex(const std::string& variable) const
86{
87 VariableIndexMap::const_iterator it = variable_index_map_.find(variable);
88 if (it == variable_index_map_.end())
89 throw Exception("Could not find variable '" + variable + "' to get bounds for within joint '" + name_ + "'");
90 return it->second;
91}
92
93bool JointModel::harmonizePosition(double* /*values*/, const Bounds& /*other_bounds*/) const
94{
95 return false;
96}
97
98bool JointModel::enforceVelocityBounds(double* values, const Bounds& other_bounds) const
99{
100 bool change = false;
101 for (std::size_t i = 0; i < other_bounds.size(); ++i)
102 {
103 if (other_bounds[i].max_velocity_ < values[i])
104 {
105 values[i] = other_bounds[i].max_velocity_;
106 change = true;
107 }
108 else if (other_bounds[i].min_velocity_ > values[i])
109 {
110 values[i] = other_bounds[i].min_velocity_;
111 change = true;
112 }
113 }
114 return change;
115}
116
117bool JointModel::satisfiesVelocityBounds(const double* values, const Bounds& other_bounds, double margin) const
118{
119 for (std::size_t i = 0; i < other_bounds.size(); ++i)
120 {
121 if (!other_bounds[i].velocity_bounded_)
122 {
123 continue;
124 }
125 if (other_bounds[i].max_velocity_ + margin < values[i])
126 {
127 return false;
128 }
129 else if (other_bounds[i].min_velocity_ - margin > values[i])
130 {
131 return false;
132 }
133 }
134 return true;
135}
136
137bool JointModel::satisfiesAccelerationBounds(const double* values, const Bounds& other_bounds, double margin) const
138{
139 for (std::size_t i = 0; i < other_bounds.size(); ++i)
140 {
141 if (!other_bounds[i].acceleration_bounded_)
142 {
143 continue;
144 }
145 if (other_bounds[i].max_acceleration_ + margin < values[i])
146 {
147 return false;
148 }
149 else if (other_bounds[i].min_acceleration_ - margin > values[i])
150 {
151 return false;
152 }
153 }
154 return true;
155}
156
157bool JointModel::satisfiesJerkBounds(const double* values, const Bounds& other_bounds, double margin) const
158{
159 for (std::size_t i = 0; i < other_bounds.size(); ++i)
160 {
161 if (!other_bounds[i].jerk_bounded_)
162 {
163 continue;
164 }
165 if (other_bounds[i].max_jerk_ + margin < values[i])
166 {
167 return false;
168 }
169 else if (other_bounds[i].min_jerk_ - margin > values[i])
170 {
171 return false;
172 }
173 }
174 return true;
175}
176
177const VariableBounds& JointModel::getVariableBounds(const std::string& variable) const
178{
179 return variable_bounds_[getLocalVariableIndex(variable)];
180}
181
182void JointModel::setVariableBounds(const std::string& variable, const VariableBounds& bounds)
183{
184 variable_bounds_[getLocalVariableIndex(variable)] = bounds;
186}
187
188void JointModel::setVariableBounds(const std::vector<moveit_msgs::msg::JointLimits>& jlim)
189{
190 for (std::size_t j = 0; j < variable_names_.size(); ++j)
191 {
192 for (const moveit_msgs::msg::JointLimits& joint_limit : jlim)
193 {
194 if (joint_limit.joint_name == variable_names_[j])
195 {
196 variable_bounds_[j].position_bounded_ = joint_limit.has_position_limits;
197 if (joint_limit.has_position_limits)
198 {
199 variable_bounds_[j].min_position_ = joint_limit.min_position;
200 variable_bounds_[j].max_position_ = joint_limit.max_position;
201 }
202 variable_bounds_[j].velocity_bounded_ = joint_limit.has_velocity_limits;
203 if (joint_limit.has_velocity_limits)
204 {
205 variable_bounds_[j].min_velocity_ = -joint_limit.max_velocity;
206 variable_bounds_[j].max_velocity_ = joint_limit.max_velocity;
207 }
208 variable_bounds_[j].acceleration_bounded_ = joint_limit.has_acceleration_limits;
209 if (joint_limit.has_acceleration_limits)
210 {
211 variable_bounds_[j].min_acceleration_ = -joint_limit.max_acceleration;
212 variable_bounds_[j].max_acceleration_ = joint_limit.max_acceleration;
213 }
214 variable_bounds_[j].jerk_bounded_ = joint_limit.has_jerk_limits;
215 if (joint_limit.has_jerk_limits)
216 {
217 variable_bounds_[j].min_jerk_ = -joint_limit.max_jerk;
218 variable_bounds_[j].max_jerk_ = joint_limit.max_jerk;
219 }
220 break;
221 }
222 }
223 }
225}
226
228{
229 variable_bounds_msg_.clear();
230 for (std::size_t i = 0; i < variable_bounds_.size(); ++i)
231 {
232 moveit_msgs::msg::JointLimits lim;
233 lim.joint_name = variable_names_[i];
234 lim.has_position_limits = variable_bounds_[i].position_bounded_;
235 lim.min_position = variable_bounds_[i].min_position_;
236 lim.max_position = variable_bounds_[i].max_position_;
237 lim.has_velocity_limits = variable_bounds_[i].velocity_bounded_;
238 lim.max_velocity = std::min(fabs(variable_bounds_[i].min_velocity_), fabs(variable_bounds_[i].max_velocity_));
239 lim.has_acceleration_limits = variable_bounds_[i].acceleration_bounded_;
240 lim.max_acceleration =
241 std::min(fabs(variable_bounds_[i].min_acceleration_), fabs(variable_bounds_[i].max_acceleration_));
242 lim.has_jerk_limits = variable_bounds_[i].jerk_bounded_;
243 lim.max_jerk = std::min(fabs(variable_bounds_[i].min_jerk_), fabs(variable_bounds_[i].max_jerk_));
244 variable_bounds_msg_.push_back(lim);
245 }
246}
247
248void JointModel::setMimic(const JointModel* mimic, double factor, double offset)
249{
250 mimic_ = mimic;
251 mimic_factor_ = factor;
252 mimic_offset_ = offset;
253}
254
256{
257 mimic_requests_.push_back(joint);
258}
259
261{
262 descendant_joint_models_.push_back(joint);
263 if (joint->getType() != FIXED)
264 non_fixed_descendant_joint_models_.push_back(joint);
265}
266
268{
269 descendant_link_models_.push_back(link);
270}
271
272namespace
273{
274inline void printBoundHelper(std::ostream& out, double v)
275{
276 if (v <= -std::numeric_limits<double>::infinity())
277 {
278 out << "-inf";
279 }
280 else if (v >= std::numeric_limits<double>::infinity())
281 {
282 out << "inf";
283 }
284 else
285 {
286 out << v;
287 }
288}
289} // namespace
290
291std::ostream& operator<<(std::ostream& out, const VariableBounds& b)
292{
293 out << "P." << (b.position_bounded_ ? "bounded" : "unbounded") << " [";
294 printBoundHelper(out, b.min_position_);
295 out << ", ";
296 printBoundHelper(out, b.max_position_);
297 out << "]; "
298 << "V." << (b.velocity_bounded_ ? "bounded" : "unbounded") << " [";
299 printBoundHelper(out, b.min_velocity_);
300 out << ", ";
301 printBoundHelper(out, b.max_velocity_);
302 out << "]; "
303 << "A." << (b.acceleration_bounded_ ? "bounded" : "unbounded") << " [";
304 printBoundHelper(out, b.min_acceleration_);
305 out << ", ";
306 printBoundHelper(out, b.max_acceleration_);
307 out << "]; "
308 << "J." << (b.jerk_bounded_ ? "bounded" : "unbounded") << " [";
309 printBoundHelper(out, b.min_jerk_);
310 out << ", ";
311 printBoundHelper(out, b.max_jerk_);
312 out << "];";
313 return out;
314}
315
316} // end of namespace core
317} // end of namespace moveit
This may be thrown if unrecoverable errors occur.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
bool satisfiesJerkBounds(const double *values, double margin=0.0) const
Check if the set of jerks for the variables of this joint are within bounds.
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.
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.
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.
const Bounds & getVariableBounds() const
Get the variable bounds for this joint, in the same order as the names returned by getVariableNames()
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,...
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.
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.