moveit2
The MoveIt Motion Planning Framework for ROS 2.
revolute_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 
39 #include <geometric_shapes/check_isometry.h>
40 #include <algorithm>
41 #include <cmath>
42 
43 namespace moveit
44 {
45 namespace core
46 {
47 RevoluteJointModel::RevoluteJointModel(const std::string& name, size_t joint_index, size_t first_variable_index)
48  : JointModel(name, joint_index, first_variable_index)
49  , axis_(0.0, 0.0, 0.0)
50  , continuous_(false)
51  , x2_(0.0)
52  , y2_(0.0)
53  , z2_(0.0)
54  , xy_(0.0)
55  , xz_(0.0)
56  , yz_(0.0)
57 {
58  type_ = REVOLUTE;
59  variable_names_.push_back(getName());
60  variable_bounds_.resize(1);
61  variable_bounds_[0].position_bounded_ = true;
62  variable_bounds_[0].min_position_ = -M_PI;
63  variable_bounds_[0].max_position_ = M_PI;
66 }
67 
69 {
70  return 1;
71 }
72 
74 {
75  axis_ = axis.normalized();
76  x2_ = axis_.x() * axis_.x();
77  y2_ = axis_.y() * axis_.y();
78  z2_ = axis_.z() * axis_.z();
79  xy_ = axis_.x() * axis_.y();
80  xz_ = axis_.x() * axis_.z();
81  yz_ = axis_.y() * axis_.z();
82 }
83 
85 {
86  continuous_ = flag;
87  if (flag)
88  {
89  variable_bounds_[0].position_bounded_ = false;
90  variable_bounds_[0].min_position_ = -M_PI;
91  variable_bounds_[0].max_position_ = M_PI;
92  }
93  else
94  variable_bounds_[0].position_bounded_ = true;
96 }
97 
98 double RevoluteJointModel::getMaximumExtent(const Bounds& /*other_bounds*/) const
99 {
100  return variable_bounds_[0].max_position_ - variable_bounds_[0].min_position_;
101 }
102 
103 void RevoluteJointModel::getVariableDefaultPositions(double* values, const Bounds& bounds) const
104 {
105  // if zero is a valid value
106  if (bounds[0].min_position_ <= 0.0 && bounds[0].max_position_ >= 0.0)
107  {
108  values[0] = 0.0;
109  }
110  else
111  {
112  values[0] = (bounds[0].min_position_ + bounds[0].max_position_) / 2.0;
113  }
114 }
115 
116 void RevoluteJointModel::getVariableRandomPositions(random_numbers::RandomNumberGenerator& rng, double* values,
117  const Bounds& bounds) const
118 {
119  values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
120 }
121 
122 void RevoluteJointModel::getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator& rng, double* values,
123  const Bounds& bounds, const double* near,
124  const double distance) const
125 {
126  if (continuous_)
127  {
128  values[0] = rng.uniformReal(near[0] - distance, near[0] + distance);
129  enforcePositionBounds(values, bounds);
130  }
131  else
132  {
133  values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
134  std::min(bounds[0].max_position_, near[0] + distance));
135  }
136 }
137 
138 void RevoluteJointModel::interpolate(const double* from, const double* to, const double t, double* state) const
139 {
140  if (continuous_)
141  {
142  double diff = to[0] - from[0];
143  if (fabs(diff) <= M_PI)
144  {
145  state[0] = from[0] + diff * t;
146  }
147  else
148  {
149  if (diff > 0.0)
150  {
151  diff = 2.0 * M_PI - diff;
152  }
153  else
154  {
155  diff = -2.0 * M_PI - diff;
156  }
157  state[0] = from[0] - diff * t;
158  // input states are within bounds, so the following check is sufficient
159  if (state[0] > M_PI)
160  {
161  state[0] -= 2.0 * M_PI;
162  }
163  else if (state[0] < -M_PI)
164  {
165  state[0] += 2.0 * M_PI;
166  }
167  }
168  }
169  else
170  state[0] = from[0] + (to[0] - from[0]) * t;
171 }
172 
173 double RevoluteJointModel::distance(const double* values1, const double* values2) const
174 {
175  if (continuous_)
176  {
177  double d = fmod(fabs(values1[0] - values2[0]), 2.0 * M_PI);
178  return (d > M_PI) ? 2.0 * M_PI - d : d;
179  }
180  else
181  return fabs(values1[0] - values2[0]);
182 }
183 
184 bool RevoluteJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds, double margin) const
185 {
186  if (continuous_)
187  {
188  return true;
189  }
190  else
191  {
192  return !(values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin);
193  }
194 }
195 
196 bool RevoluteJointModel::harmonizePosition(double* values, const JointModel::Bounds& other_bounds) const
197 {
198  bool modified = false;
199  if (*values < other_bounds[0].min_position_)
200  {
201  while (*values + 2 * M_PI <= other_bounds[0].max_position_)
202  {
203  *values += 2 * M_PI;
204  modified = true;
205  }
206  }
207  else if (*values > other_bounds[0].max_position_)
208  {
209  while (*values - 2 * M_PI >= other_bounds[0].min_position_)
210  {
211  *values -= 2 * M_PI;
212  modified = true;
213  }
214  }
215  return modified;
216 }
217 
218 bool RevoluteJointModel::enforcePositionBounds(double* values, const Bounds& bounds) const
219 {
220  if (continuous_)
221  {
222  double& v = values[0];
223  if (v <= -M_PI || v > M_PI)
224  {
225  v = fmod(v, 2.0 * M_PI);
226  if (v <= -M_PI)
227  {
228  v += 2.0 * M_PI;
229  }
230  else if (v > M_PI)
231  {
232  v -= 2.0 * M_PI;
233  }
234  }
235  }
236  else
237  {
238  if (values[0] < bounds[0].min_position_)
239  {
240  values[0] = bounds[0].min_position_;
241  }
242  else if (values[0] > bounds[0].max_position_)
243  {
244  values[0] = bounds[0].max_position_;
245  }
246  }
247  return true;
248 }
249 
250 void RevoluteJointModel::computeTransform(const double* joint_values, Eigen::Isometry3d& transf) const
251 {
252  const double c = cos(joint_values[0]);
253  const double s = sin(joint_values[0]);
254  const double t = 1.0 - c;
255  const double txy = t * xy_;
256  const double txz = t * xz_;
257  const double tyz = t * yz_;
258 
259  const double zs = axis_.z() * s;
260  const double ys = axis_.y() * s;
261  const double xs = axis_.x() * s;
262 
263  // column major
264  double* d = transf.data();
265 
266  d[0] = t * x2_ + c;
267  d[1] = txy + zs;
268  d[2] = txz - ys;
269  d[3] = 0.0;
270 
271  d[4] = txy - zs;
272  d[5] = t * y2_ + c;
273  d[6] = tyz + xs;
274  d[7] = 0.0;
275 
276  d[8] = txz + ys;
277  d[9] = tyz - xs;
278  d[10] = t * z2_ + c;
279  d[11] = 0.0;
280 
281  d[12] = 0.0;
282  d[13] = 0.0;
283  d[14] = 0.0;
284  d[15] = 1.0;
285 
286  // transf = Eigen::Isometry3d(Eigen::AngleAxisd(joint_values[0], axis_));
287 }
288 
289 void RevoluteJointModel::computeVariablePositions(const Eigen::Isometry3d& transf, double* joint_values) const
290 {
291  ASSERT_ISOMETRY(transf) // unsanitized input, could contain a non-isometry
292  Eigen::Quaterniond q(transf.linear());
293  q.normalize();
294  size_t max_idx;
295  axis_.array().abs().maxCoeff(&max_idx);
296  joint_values[0] = 2. * atan2(q.vec()[max_idx] / axis_[max_idx], q.w());
297 }
298 
299 } // end of namespace core
300 } // end of namespace moveit
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
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
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 ...
bool continuous_
Flag indicating whether this joint wraps around.
Eigen::Vector3d axis_
The axis of the joint.
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 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.
bool harmonizePosition(double *values, const Bounds &other_bounds) const override
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...
EIGEN_MAKE_ALIGNED_OPERATOR_NEW RevoluteJointModel(const std::string &name, size_t joint_index, size_t first_variable_index)
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....
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 setAxis(const Eigen::Vector3d &axis)
Set the axis of rotation.
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,...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
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