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 
39 #include <boost/math/constants/constants.hpp>
40 #include <limits>
41 #include <cmath>
42 
43 namespace moveit
44 {
45 namespace core
46 {
47 PlanarJointModel::PlanarJointModel(const std::string& name) : JointModel(name), angular_distance_weight_(1.0)
48 {
49  type_ = PLANAR;
50 
51  local_variable_names_.push_back("x");
52  local_variable_names_.push_back("y");
53  local_variable_names_.push_back("theta");
54  for (int i = 0; i < 3; ++i)
55  {
56  variable_names_.push_back(name_ + "/" + local_variable_names_[i]);
58  }
59 
60  variable_bounds_.resize(3);
61  variable_bounds_[0].position_bounded_ = true;
62  variable_bounds_[1].position_bounded_ = true;
63  variable_bounds_[2].position_bounded_ = false;
64 
65  variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
66  variable_bounds_[0].max_position_ = std::numeric_limits<double>::infinity();
67  variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
68  variable_bounds_[1].max_position_ = std::numeric_limits<double>::infinity();
69  variable_bounds_[2].min_position_ = -boost::math::constants::pi<double>();
70  variable_bounds_[2].max_position_ = boost::math::constants::pi<double>();
71 
73 }
74 
76 {
77  return 3;
78 }
79 
80 double PlanarJointModel::getMaximumExtent(const Bounds& other_bounds) const
81 {
82  double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
83  double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
84  return sqrt(dx * dx + dy * dy) + boost::math::constants::pi<double>() * angular_distance_weight_;
85 }
86 
87 void PlanarJointModel::getVariableDefaultPositions(double* values, const Bounds& bounds) const
88 {
89  for (unsigned int i = 0; i < 2; ++i)
90  {
91  // if zero is a valid value
92  if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
93  values[i] = 0.0;
94  else
95  values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
96  }
97  values[2] = 0.0;
98 }
99 
101  const Bounds& bounds) const
102 {
103  if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
104  bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
105  values[0] = 0.0;
106  else
107  values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
108  if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
109  bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
110  values[1] = 0.0;
111  else
112  values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
113  values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
114 }
115 
117  const Bounds& bounds, const double* near,
118  const double distance) const
119 {
120  if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
121  bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
122  values[0] = 0.0;
123  else
124  values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
125  std::min(bounds[0].max_position_, near[0] + distance));
126  if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
127  bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
128  values[1] = 0.0;
129  else
130  values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
131  std::min(bounds[1].max_position_, near[1] + distance));
132 
133  double da = angular_distance_weight_ * distance;
134  // limit the sampling range to 2pi to work correctly even if the distance is very large
135  if (da > boost::math::constants::pi<double>())
136  da = boost::math::constants::pi<double>();
137  values[2] = rng.uniformReal(near[2] - da, near[2] + da);
138  normalizeRotation(values);
139 }
140 
141 void PlanarJointModel::interpolate(const double* from, const double* to, const double t, double* state) const
142 {
143  // interpolate position
144  state[0] = from[0] + (to[0] - from[0]) * t;
145  state[1] = from[1] + (to[1] - from[1]) * t;
146 
147  // interpolate angle
148  double diff = to[2] - from[2];
149  if (fabs(diff) <= boost::math::constants::pi<double>())
150  state[2] = from[2] + diff * t;
151  else
152  {
153  if (diff > 0.0)
154  diff = 2.0 * boost::math::constants::pi<double>() - diff;
155  else
156  diff = -2.0 * boost::math::constants::pi<double>() - diff;
157  state[2] = from[2] - diff * t;
158  // input states are within bounds, so the following check is sufficient
159  if (state[2] > boost::math::constants::pi<double>())
160  state[2] -= 2.0 * boost::math::constants::pi<double>();
161  else if (state[2] < -boost::math::constants::pi<double>())
162  state[2] += 2.0 * boost::math::constants::pi<double>();
163  }
164 }
165 
166 double PlanarJointModel::distance(const double* values1, const double* values2) const
167 {
168  double dx = values1[0] - values2[0];
169  double dy = values1[1] - values2[1];
170 
171  double d = fabs(values1[2] - values2[2]);
172  d = (d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - d : d;
173  return sqrt(dx * dx + dy * dy) + angular_distance_weight_ * d;
174 }
175 
176 bool PlanarJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds, double margin) const
177 {
178  for (unsigned int i = 0; i < 3; ++i)
179  if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
180  return false;
181  return true;
182 }
183 
184 bool PlanarJointModel::normalizeRotation(double* values) const
185 {
186  double& v = values[2];
187  if (v >= -boost::math::constants::pi<double>() && v <= boost::math::constants::pi<double>())
188  return false;
189  v = fmod(v, 2.0 * boost::math::constants::pi<double>());
190  if (v < -boost::math::constants::pi<double>())
191  v += 2.0 * boost::math::constants::pi<double>();
192  else if (v > boost::math::constants::pi<double>())
193  v -= 2.0 * boost::math::constants::pi<double>();
194  return true;
195 }
196 
197 bool PlanarJointModel::enforcePositionBounds(double* values, const Bounds& bounds) const
198 {
199  bool result = normalizeRotation(values);
200  for (unsigned int i = 0; i < 2; ++i)
201  {
202  if (values[i] < bounds[i].min_position_)
203  {
204  values[i] = bounds[i].min_position_;
205  result = true;
206  }
207  else if (values[i] > bounds[i].max_position_)
208  {
209  values[i] = bounds[i].max_position_;
210  result = true;
211  }
212  }
213  return result;
214 }
215 
216 void PlanarJointModel::computeTransform(const double* joint_values, Eigen::Affine3d& transf) const
217 {
218  transf = Eigen::Affine3d(Eigen::Translation3d(joint_values[0], joint_values[1], 0.0) *
219  Eigen::AngleAxisd(joint_values[2], Eigen::Vector3d::UnitZ()));
220 }
221 
222 void PlanarJointModel::computeVariablePositions(const Eigen::Affine3d& transf, double* joint_values) const
223 {
224  joint_values[0] = transf.translation().x();
225  joint_values[1] = transf.translation().y();
226 
227  Eigen::Quaterniond q(transf.linear());
228  // taken from Bullet
229  double s_squared = 1.0 - (q.w() * q.w());
230  if (s_squared < 10.0 * std::numeric_limits<double>::epsilon())
231  joint_values[2] = 0.0;
232  else
233  {
234  double s = 1.0 / sqrt(s_squared);
235  joint_values[2] = (acos(q.w()) * 2.0f) * (q.z() * s);
236  }
237 }
238 
239 } // end of namespace core
240 } // end of namespace moveit
d
PlanarJointModel(const std::string &name)
std::vector< std::string > local_variable_names_
The local names to use for the variables that make up this joint.
Definition: joint_model.h:457
f
std::string name_
Name of the joint.
Definition: joint_model.h:451
XmlRpcServer s
Bounds variable_bounds_
The bounds for each variable (low, high) in the same order as variable_names_.
Definition: joint_model.h:463
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
JointType type_
The type of joint.
Definition: joint_model.h:454
double getMaximumExtent() const
Definition: joint_model.h:431
virtual void interpolate(const double *from, const double *to, const double t, double *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
virtual bool satisfiesPositionBounds(const double *values, const Bounds &other_bounds, double margin) const
Check if the set of position values for the variables of this joint are within bounds, up to some margin.
virtual bool enforcePositionBounds(double *values, const Bounds &other_bounds) const
Force the specified values to be inside bounds and normalized. Quaternions are normalized, continuous joints are made between -Pi and Pi. Return true if changes were made.
virtual void getVariableRandomPositionsNearBy(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds, const double *near, const double distance) const
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
virtual void getVariableDefaultPositions(double *values, const Bounds &other_bounds) const
Provide a default value for the joint given the joint variable bounds. Most joints will use the defau...
double uniformReal(double lower_bound, double upper_bound)
VariableIndexMap variable_index_map_
Map from variable names to the corresponding index in variable_names_ (indexing makes sense within th...
Definition: joint_model.h:469
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
A joint from the robot. Models the transform that this joint applies in the kinematic chain...
Definition: joint_model.h:108
virtual double distance(const double *values1, const double *values2) const
Compute the distance between two joint states of the same model (represented by the variable values) ...
INLINE Rall1d< T, V, S > acos(const Rall1d< T, V, S > &x)
virtual void computeTransform(const double *joint_values, Eigen::Affine3d &transf) const
Given the joint values for a joint, compute the corresponding transform.
virtual unsigned int getStateSpaceDimension() const
Get the dimension of the state space that corresponds to this joint.
std::vector< std::string > variable_names_
The full names to use for the variables that make up this joint.
Definition: joint_model.h:460
virtual void getVariableRandomPositions(random_numbers::RandomNumberGenerator &rng, double *values, const Bounds &other_bounds) const
Provide random values for the joint variables (within specified bounds). Enough memory is assumed to ...
Main namespace for MoveIt!
std::vector< VariableBounds > Bounds
The datatype for the joint bounds.
Definition: joint_model.h:123
bool normalizeRotation(double *values) const
virtual void computeVariablePositions(const Eigen::Affine3d &transf, double *joint_values) const
Given the transform generated by joint, compute the corresponding joint values.


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:33