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