moveit2
The MoveIt Motion Planning Framework for ROS 2.
floating_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 <cmath>
39 #include <Eigen/Geometry>
40 #include <geometric_shapes/check_isometry.h>
41 #include <limits>
43 #include <rclcpp/logger.hpp>
44 #include <rclcpp/logging.hpp>
45 #include <moveit/utils/logger.hpp>
46 
47 namespace moveit
48 {
49 namespace core
50 {
51 namespace
52 {
53 constexpr size_t STATE_SPACE_DIMENSION = 7;
54 
55 rclcpp::Logger getLogger()
56 {
57  return moveit::getLogger("floating_joint_model");
58 }
59 
60 } // namespace
61 
62 FloatingJointModel::FloatingJointModel(const std::string& name, size_t joint_index, size_t first_variable_index)
63  : JointModel(name, joint_index, first_variable_index), angular_distance_weight_(1.0)
64 {
65  type_ = FLOATING;
66  local_variable_names_.push_back("trans_x");
67  local_variable_names_.push_back("trans_y");
68  local_variable_names_.push_back("trans_z");
69  local_variable_names_.push_back("rot_x");
70  local_variable_names_.push_back("rot_y");
71  local_variable_names_.push_back("rot_z");
72  local_variable_names_.push_back("rot_w");
73  for (size_t i = 0; i < STATE_SPACE_DIMENSION; ++i)
74  {
75  variable_names_.push_back(getName() + "/" + local_variable_names_[i]);
77  }
78 
79  variable_bounds_.resize(7);
80 
81  variable_bounds_[0].position_bounded_ = true;
82  variable_bounds_[1].position_bounded_ = true;
83  variable_bounds_[2].position_bounded_ = true;
84  variable_bounds_[3].position_bounded_ = true;
85  variable_bounds_[4].position_bounded_ = true;
86  variable_bounds_[5].position_bounded_ = true;
87  variable_bounds_[6].position_bounded_ = true;
88 
89  variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
90  variable_bounds_[0].max_position_ = std::numeric_limits<double>::infinity();
91  variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
92  variable_bounds_[1].max_position_ = std::numeric_limits<double>::infinity();
93  variable_bounds_[2].min_position_ = -std::numeric_limits<double>::infinity();
94  variable_bounds_[2].max_position_ = std::numeric_limits<double>::infinity();
95  variable_bounds_[3].min_position_ = -1.0;
96  variable_bounds_[3].max_position_ = 1.0;
97  variable_bounds_[4].min_position_ = -1.0;
98  variable_bounds_[4].max_position_ = 1.0;
99  variable_bounds_[5].min_position_ = -1.0;
100  variable_bounds_[5].max_position_ = 1.0;
101  variable_bounds_[6].min_position_ = -1.0;
102  variable_bounds_[6].max_position_ = 1.0;
103 
105 }
106 
107 double FloatingJointModel::getMaximumExtent(const Bounds& other_bounds) const
108 {
109  double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
110  double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
111  double dz = other_bounds[2].max_position_ - other_bounds[2].min_position_;
112  return sqrt(dx * dx + dy * dy + dz * dz) + M_PI * 0.5 * angular_distance_weight_;
113 }
114 
115 double FloatingJointModel::distance(const double* values1, const double* values2) const
116 {
117  return distanceTranslation(values1, values2) + angular_distance_weight_ * distanceRotation(values1, values2);
118 }
119 
120 double FloatingJointModel::distanceTranslation(const double* values1, const double* values2) const
121 {
122  double dx = values1[0] - values2[0];
123  double dy = values1[1] - values2[1];
124  double dz = values1[2] - values2[2];
125  return sqrt(dx * dx + dy * dy + dz * dz);
126 }
127 
128 double FloatingJointModel::distanceRotation(const double* values1, const double* values2) const
129 {
130  // The values are in "xyzw" order but Eigen expects "wxyz".
131  const auto q1 = Eigen::Quaterniond(values1[6], values1[3], values1[4], values1[5]).normalized();
132  const auto q2 = Eigen::Quaterniond(values2[6], values2[3], values2[4], values2[5]).normalized();
133  return q2.angularDistance(q1);
134 }
135 
136 void FloatingJointModel::interpolate(const double* from, const double* to, const double t, double* state) const
137 {
138  // interpolate position
139  state[0] = from[0] + (to[0] - from[0]) * t;
140  state[1] = from[1] + (to[1] - from[1]) * t;
141  state[2] = from[2] + (to[2] - from[2]) * t;
142 
143  // Check if the quaternions are significantly different
144  if (abs(from[3] - to[3]) + abs(from[4] - to[4]) + abs(from[5] - to[5]) + abs(from[6] - to[6]) >
145  std::numeric_limits<double>::epsilon())
146  {
147  // Note the ordering: Eigen takes w first!
148  Eigen::Quaterniond q1(from[6], from[3], from[4], from[5]);
149  Eigen::Quaterniond q2(to[6], to[3], to[4], to[5]);
150 
151  Eigen::Quaterniond q = q1.slerp(t, q2);
152 
153  state[3] = q.x();
154  state[4] = q.y();
155  state[5] = q.z();
156  state[6] = q.w();
157  }
158  else
159  {
160  state[3] = from[3];
161  state[4] = from[4];
162  state[5] = from[5];
163  state[6] = from[6];
164  }
165 }
166 
167 bool FloatingJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds, double margin) const
168 {
169  if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
170  return false;
171  if (values[1] < bounds[1].min_position_ - margin || values[1] > bounds[1].max_position_ + margin)
172  return false;
173  if (values[2] < bounds[2].min_position_ - margin || values[2] > bounds[2].max_position_ + margin)
174  return false;
175  double norm_sqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
176  return fabs(norm_sqr - 1.0) <= std::numeric_limits<double>::epsilon() * 10.0;
177 }
178 
179 bool FloatingJointModel::normalizeRotation(double* values) const
180 {
181  // normalize the quaternion if we need to
182  double norm_sqr = values[3] * values[3] + values[4] * values[4] + values[5] * values[5] + values[6] * values[6];
183  if (fabs(norm_sqr - 1.0) > std::numeric_limits<double>::epsilon() * 100.0)
184  {
185  double norm = sqrt(norm_sqr);
186  if (norm < std::numeric_limits<double>::epsilon() * 100.0)
187  {
188  RCLCPP_WARN(getLogger(), "Quaternion is zero in RobotState representation. Setting to identity");
189  values[3] = 0.0;
190  values[4] = 0.0;
191  values[5] = 0.0;
192  values[6] = 1.0;
193  }
194  else
195  {
196  values[3] /= norm;
197  values[4] /= norm;
198  values[5] /= norm;
199  values[6] /= norm;
200  }
201  return true;
202  }
203  else
204  return false;
205 }
206 
208 {
209  return STATE_SPACE_DIMENSION;
210 }
211 
212 bool FloatingJointModel::enforcePositionBounds(double* values, const Bounds& bounds) const
213 {
214  bool result = normalizeRotation(values);
215  for (unsigned int i = 0; i < 3; ++i)
216  {
217  if (values[i] < bounds[i].min_position_)
218  {
219  values[i] = bounds[i].min_position_;
220  result = true;
221  }
222  else if (values[i] > bounds[i].max_position_)
223  {
224  values[i] = bounds[i].max_position_;
225  result = true;
226  }
227  }
228  return result;
229 }
230 
231 void FloatingJointModel::computeTransform(const double* joint_values, Eigen::Isometry3d& transf) const
232 {
233  transf = Eigen::Isometry3d(
234  Eigen::Translation3d(joint_values[0], joint_values[1], joint_values[2]) *
235  Eigen::Quaterniond(joint_values[6], joint_values[3], joint_values[4], joint_values[5]).normalized());
236 }
237 
238 void FloatingJointModel::computeVariablePositions(const Eigen::Isometry3d& transf, double* joint_values) const
239 {
240  joint_values[0] = transf.translation().x();
241  joint_values[1] = transf.translation().y();
242  joint_values[2] = transf.translation().z();
243  ASSERT_ISOMETRY(transf) // unsanitized input, could contain non-isometry
244  Eigen::Quaterniond q(transf.linear());
245  joint_values[3] = q.x();
246  joint_values[4] = q.y();
247  joint_values[5] = q.z();
248  joint_values[6] = q.w();
249 }
250 
251 void FloatingJointModel::getVariableDefaultPositions(double* values, const Bounds& bounds) const
252 {
253  for (unsigned int i = 0; i < 3; ++i)
254  {
255  // if zero is a valid value
256  if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
257  {
258  values[i] = 0.0;
259  }
260  else
261  {
262  values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
263  }
264  }
265 
266  values[3] = 0.0;
267  values[4] = 0.0;
268  values[5] = 0.0;
269  values[6] = 1.0;
270 }
271 
272 void FloatingJointModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
273  const Bounds& bounds) const
274 {
275  if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
276  bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
277  {
278  values[0] = 0.0;
279  }
280  else
281  {
282  values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
283  }
284  if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
285  bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
286  {
287  values[1] = 0.0;
288  }
289  else
290  {
291  values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
292  }
293  if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
294  bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
295  {
296  values[2] = 0.0;
297  }
298  else
299  {
300  values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
301  }
302 
303  double q[4];
304  rng.quaternion(q);
305  values[3] = q[0];
306  values[4] = q[1];
307  values[5] = q[2];
308  values[6] = q[3];
309 }
310 
311 void FloatingJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
312  const Bounds& bounds, const double* near,
313  const double distance) const
314 {
315  if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
316  bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
317  {
318  values[0] = 0.0;
319  }
320  else
321  {
322  values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
323  std::min(bounds[0].max_position_, near[0] + distance));
324  }
325  if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
326  bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
327  {
328  values[1] = 0.0;
329  }
330  else
331  {
332  values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
333  std::min(bounds[1].max_position_, near[1] + distance));
334  }
335  if (bounds[2].max_position_ >= std::numeric_limits<double>::infinity() ||
336  bounds[2].min_position_ <= -std::numeric_limits<double>::infinity())
337  {
338  values[2] = 0.0;
339  }
340  else
341  {
342  values[2] = rng.uniformReal(std::max(bounds[2].min_position_, near[2] - distance),
343  std::min(bounds[2].max_position_, near[2] + distance));
344  }
345 
346  double da = angular_distance_weight_ * distance;
347  if (da >= .25 * M_PI)
348  {
349  double q[4];
350  rng.quaternion(q);
351  values[3] = q[0];
352  values[4] = q[1];
353  values[5] = q[2];
354  values[6] = q[3];
355  }
356  else
357  {
358  // taken from OMPL
359  // sample angle & axis
360  double ax = rng.gaussian01();
361  double ay = rng.gaussian01();
362  double az = rng.gaussian01();
363  double angle = 2.0 * pow(rng.uniform01(), 1.0 / 3.0) * da;
364  // convert to quaternion
365  double q[4];
366  double norm = sqrt(ax * ax + ay * ay + az * az);
367  if (norm < 1e-6)
368  {
369  q[0] = q[1] = q[2] = 0.0;
370  q[3] = 1.0;
371  }
372  else
373  {
374  double s = sin(angle / 2.0);
375  q[0] = s * ax / norm;
376  q[1] = s * ay / norm;
377  q[2] = s * az / norm;
378  q[3] = cos(angle / 2.0);
379  }
380  // multiply quaternions: near * q
381  values[3] = near[6] * q[0] + near[3] * q[3] + near[4] * q[2] - near[5] * q[1];
382  values[4] = near[6] * q[1] + near[4] * q[3] + near[5] * q[0] - near[3] * q[2];
383  values[5] = near[6] * q[2] + near[5] * q[3] + near[3] * q[1] - near[4] * q[0];
384  values[6] = near[6] * q[3] - near[3] * q[0] - near[4] * q[1] - near[5] * q[2];
385  }
386 }
387 
388 } // end of namespace core
389 } // end of namespace moveit
double distanceRotation(const double *values1, const double *values2) const
Get the distance between the rotation components of two states.
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 ...
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....
bool normalizeRotation(double *values) const
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 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...
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 ...
bool enforcePositionBounds(double *values, const Bounds &other_bounds) const override
Force the specified values to be inside bounds and normalized. Quaternions are normalized,...
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 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 ...
double distanceTranslation(const double *values1, const double *values2) const
Get the distance between the translation components of two states.
FloatingJointModel(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...
unsigned int getStateSpaceDimension() const override
Get the dimension of the state space that corresponds to this joint.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
Definition: joint_model.h:506
JointType type_
The type of joint.
Definition: joint_model.h:491
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
Definition: joint_model.h:500
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:131
const std::string & getName() const
Get the name of the joint.
Definition: joint_model.h:145
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
Definition: joint_model.h:494
double getMaximumExtent() const
Definition: joint_model.h:459
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
Definition: joint_model.h:497
Main namespace for MoveIt.
Definition: exceptions.h:43
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
name
Definition: setup.py:7