moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
planar_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
38#include <angles/angles.h>
39#include <cmath>
40#include <geometric_shapes/check_isometry.h>
41#include <limits>
43
44namespace moveit
45{
46namespace core
47{
48PlanarJointModel::PlanarJointModel(const std::string& name, size_t joint_index, size_t first_variable_index)
49 : JointModel(name, joint_index, first_variable_index)
50 , angular_distance_weight_(1.0)
51 , motion_model_(HOLONOMIC)
52 , min_translational_distance_(1e-5)
53{
54 type_ = PLANAR;
55
56 local_variable_names_.push_back("x");
57 local_variable_names_.push_back("y");
58 local_variable_names_.push_back("theta");
59 for (int i = 0; i < 3; ++i)
60 {
61 variable_names_.push_back(getName() + "/" + local_variable_names_[i]);
63 }
64
65 variable_bounds_.resize(3);
66 variable_bounds_[0].position_bounded_ = true;
67 variable_bounds_[1].position_bounded_ = true;
68 variable_bounds_[2].position_bounded_ = false;
69
70 variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
71 variable_bounds_[0].max_position_ = std::numeric_limits<double>::infinity();
72 variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
73 variable_bounds_[1].max_position_ = std::numeric_limits<double>::infinity();
74 variable_bounds_[2].min_position_ = -M_PI;
75 variable_bounds_[2].max_position_ = M_PI;
76
78}
79
81{
82 return 3;
83}
84
85double PlanarJointModel::getMaximumExtent(const Bounds& other_bounds) const
86{
87 double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
88 double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
89 return sqrt(dx * dx + dy * dy) + M_PI * angular_distance_weight_;
90}
91
92void PlanarJointModel::getVariableDefaultPositions(double* values, const Bounds& bounds) const
93{
94 for (unsigned int i = 0; i < 2; ++i)
95 {
96 // if zero is a valid value
97 if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
98 {
99 values[i] = 0.0;
100 }
101 else
102 {
103 values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
104 }
105 }
106 values[2] = 0.0;
107}
108
109void PlanarJointModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
110 const Bounds& bounds) const
111{
112 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
113 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
114 {
115 values[0] = 0.0;
116 }
117 else
118 {
119 values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
120 }
121 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
122 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
123 {
124 values[1] = 0.0;
125 }
126 else
127 {
128 values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
129 }
130 values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
131}
132
133void PlanarJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
134 const Bounds& bounds, const double* near,
135 const double distance) const
136{
137 if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
138 bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
139 {
140 values[0] = 0.0;
141 }
142 else
143 {
144 values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
145 std::min(bounds[0].max_position_, near[0] + distance));
146 }
147 if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
148 bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
149 {
150 values[1] = 0.0;
151 }
152 else
153 {
154 values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
155 std::min(bounds[1].max_position_, near[1] + distance));
156 }
157
158 double da = angular_distance_weight_ * distance;
159 // limit the sampling range to 2pi to work correctly even if the distance is very large
160 if (da > M_PI)
161 da = M_PI;
162 values[2] = rng.uniformReal(near[2] - da, near[2] + da);
163 normalizeRotation(values);
164}
165
166void computeTurnDriveTurnGeometry(const double* from, const double* to, const double min_translational_distance,
167 double& dx, double& dy, double& initial_turn, double& drive_angle, double& final_turn)
168{
169 dx = to[0] - from[0];
170 dy = to[1] - from[1];
171 // If the translational distance between from & to states is very small, it will cause an unnecessary rotation since
172 // the robot will try to do the following rather than rotating directly to the orientation of `to` state
173 // 1- Align itself with the line connecting the origin of both states
174 // 2- Move to the origin of `to` state
175 // 3- Rotate so it have the same orientation as `to` state
176 // Example: from=[0.0, 0.0, 0.0] - to=[1e-31, 1e-31, -130°]
177 // here the robot will: rotate 45° -> move to the origin of `to` state -> rotate -175°, rather than rotating directly
178 // to -130°
179 // to fix this we added a joint property (default value is 1e-5) and make the movement pure rotation if the
180 // translational distance is less than this number
181 const double angle_straight_diff = std::hypot(dx, dy) > min_translational_distance ?
182 angles::shortest_angular_distance(from[2], std::atan2(dy, dx)) :
183 0.0;
184 const double angle_backward_diff = angles::normalize_angle(angle_straight_diff - M_PI);
185 const double move_straight_cost =
186 std::abs(angle_straight_diff) + std::abs(angles::shortest_angular_distance(from[2] + angle_straight_diff, to[2]));
187 const double move_backward_cost =
188 std::abs(angle_backward_diff) + std::abs(angles::shortest_angular_distance(from[2] + angle_backward_diff, to[2]));
189 if (move_straight_cost <= move_backward_cost)
190 {
191 initial_turn = angle_straight_diff;
192 }
193 else
194 {
195 initial_turn = angle_backward_diff;
196 }
197 drive_angle = from[2] + initial_turn;
198 final_turn = angles::shortest_angular_distance(drive_angle, to[2]);
199}
200
201void PlanarJointModel::interpolate(const double* from, const double* to, const double t, double* state) const
202{
203 if (motion_model_ == HOLONOMIC)
204 {
205 // interpolate position
206 state[0] = from[0] + (to[0] - from[0]) * t;
207 state[1] = from[1] + (to[1] - from[1]) * t;
208
209 // interpolate angle
210 double diff = to[2] - from[2];
211 if (fabs(diff) <= M_PI)
212 {
213 state[2] = from[2] + diff * t;
214 }
215 else
216 {
217 if (diff > 0.0)
218 {
219 diff = 2.0 * M_PI - diff;
220 }
221 else
222 {
223 diff = -2.0 * M_PI - diff;
224 }
225 state[2] = from[2] - diff * t;
226 // input states are within bounds, so the following check is sufficient
227 if (state[2] > M_PI)
228 {
229 state[2] -= 2.0 * M_PI;
230 }
231 else if (state[2] < -M_PI)
232 {
233 state[2] += 2.0 * M_PI;
234 }
235 }
236 }
237 else if (motion_model_ == DIFF_DRIVE)
238 {
239 double dx, dy, initial_turn, drive_angle, final_turn;
240 computeTurnDriveTurnGeometry(from, to, min_translational_distance_, dx, dy, initial_turn, drive_angle, final_turn);
241
242 double initial_d = fabs(initial_turn) * angular_distance_weight_;
243 double drive_d = hypot(dx, dy);
244 double final_d = fabs(final_turn) * angular_distance_weight_;
245
246 double total_d = initial_d + drive_d + final_d;
247
248 double initial_frac = initial_d / total_d;
249 double drive_frac = drive_d / total_d;
250 double final_frac = final_d / total_d;
251
252 double percent;
253 if (t <= initial_frac)
254 {
255 percent = t / initial_frac;
256 state[0] = from[0];
257 state[1] = from[1];
258 state[2] = from[2] + initial_turn * percent;
259 }
260 else if (t <= initial_frac + drive_frac)
261 {
262 percent = (t - initial_frac) / drive_frac;
263 state[0] = from[0] + dx * percent;
264 state[1] = from[1] + dy * percent;
265 state[2] = drive_angle;
266 }
267 else
268 {
269 percent = (t - initial_frac - drive_frac) / final_frac;
270 state[0] = to[0];
271 state[1] = to[1];
272 state[2] = drive_angle + final_turn * percent;
273 }
274 }
275}
276
277double PlanarJointModel::distance(const double* values1, const double* values2) const
278{
279 if (motion_model_ == HOLONOMIC)
280 {
281 double dx = values1[0] - values2[0];
282 double dy = values1[1] - values2[1];
283
284 double d = fabs(values1[2] - values2[2]);
285 d = (d > M_PI) ? 2.0 * M_PI - d : d;
286 return sqrt(dx * dx + dy * dy) + angular_distance_weight_ * d;
287 }
288 else if (motion_model_ == DIFF_DRIVE)
289 {
290 double dx, dy, initial_turn, drive_angle, final_turn;
291 computeTurnDriveTurnGeometry(values1, values2, min_translational_distance_, dx, dy, initial_turn, drive_angle,
292 final_turn);
293 return hypot(dx, dy) + angular_distance_weight_ * (fabs(initial_turn) + fabs(final_turn));
294 }
295
296 return 0.0;
297}
298
299bool PlanarJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds, double margin) const
300{
301 for (unsigned int i = 0; i < 3; ++i)
302 {
303 if (values[i] < bounds[i].min_position_ - margin || values[i] > bounds[i].max_position_ + margin)
304 return false;
305 }
306 return true;
307}
308
309bool PlanarJointModel::normalizeRotation(double* values) const
310{
311 double& v = values[2];
312 if (v >= -M_PI && v <= M_PI)
313 return false;
314 v = fmod(v, 2.0 * M_PI);
315 if (v < -M_PI)
316 {
317 v += 2.0 * M_PI;
318 }
319 else if (v > M_PI)
320 {
321 v -= 2.0 * M_PI;
322 }
323 return true;
324}
325
326bool PlanarJointModel::enforcePositionBounds(double* values, const Bounds& bounds) const
327{
328 bool result = normalizeRotation(values);
329 for (unsigned int i = 0; i < 2; ++i)
330 {
331 if (values[i] < bounds[i].min_position_)
332 {
333 values[i] = bounds[i].min_position_;
334 result = true;
335 }
336 else if (values[i] > bounds[i].max_position_)
337 {
338 values[i] = bounds[i].max_position_;
339 result = true;
340 }
341 }
342 return result;
343}
344
345void PlanarJointModel::computeTransform(const double* joint_values, Eigen::Isometry3d& transf) const
346{
347 transf = Eigen::Isometry3d(Eigen::Translation3d(joint_values[0], joint_values[1], 0.0) *
348 Eigen::AngleAxisd(joint_values[2], Eigen::Vector3d::UnitZ()));
349}
350
351void PlanarJointModel::computeVariablePositions(const Eigen::Isometry3d& transf, double* joint_values) const
352{
353 joint_values[0] = transf.translation().x();
354 joint_values[1] = transf.translation().y();
355
356 ASSERT_ISOMETRY(transf) // unsanitized input, could contain a non-isometry
357 Eigen::Quaterniond q(transf.linear());
358 // taken from Bullet
359 double s_squared = 1.0 - (q.w() * q.w());
360 if (s_squared < 10.0 * std::numeric_limits<double>::epsilon())
361 {
362 joint_values[2] = 0.0;
363 }
364 else
365 {
366 double s = 1.0 / sqrt(s_squared);
367 joint_values[2] = (acos(q.w()) * 2.0f) * (q.z() * s);
368 }
369}
370
371} // end of namespace core
372} // end of namespace moveit
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
JointType type_
The type of joint.
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
const std::string & getName() const
Get the name of the joint.
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
double getMaximumExtent() const
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
bool normalizeRotation(double *values) const
void interpolate(const double *from, const double *to, const double t, double *state) const override
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state....
void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const override
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
PlanarJointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
void computeTransform(const double *joint_values, Eigen::Isometry3d &transf) const override
Given the joint values for a joint, compute the corresponding transform. The computed transform is gu...
bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const override
Check if the set of position values for the variables of this joint are within bounds,...
void computeVariablePositions(const Eigen::Isometry3d &transf, double *joint_values) const override
Given the transform generated by joint, compute the corresponding joint values. Make sure the passed ...
unsigned int getStateSpaceDimension() const override
Get the dimension of the state space that corresponds to this joint.
bool enforcePositionBounds(double *values, const Bounds &other_bounds) const override
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const override
Provide a default value for the joint given the joint variable bounds. Most joints will use the defau...
double distance(const double *values1, const double *values2) const override
Compute the distance between two joint states of the same model (represented by the variable values)
void computeTurnDriveTurnGeometry(const double *from, const double *to, const double min_translational_distance, double &dx, double &dy, double &initial_turn, double &drive_angle, double &final_turn)
Compute the geometry to turn toward the target point, drive straight and then turn to target orientat...
Main namespace for MoveIt.
Definition exceptions.h:43