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 
44  : JointModel(name), angular_distance_weight_(1.0)
45 {
46  type_ = PLANAR;
47 
48  local_variable_names_.push_back("x");
49  local_variable_names_.push_back("y");
50  local_variable_names_.push_back("theta");
51  for (int i = 0; i < 3; ++i)
52  {
53  variable_names_.push_back(name_ + "/" + local_variable_names_[i]);
55  }
56 
57  variable_bounds_.resize(3);
58  variable_bounds_[0].position_bounded_ = true;
59  variable_bounds_[1].position_bounded_ = true;
60  variable_bounds_[2].position_bounded_ = false;
61 
62  variable_bounds_[0].min_position_ = -std::numeric_limits<double>::infinity();
63  variable_bounds_[0].max_position_ = std::numeric_limits<double>::infinity();
64  variable_bounds_[1].min_position_ = -std::numeric_limits<double>::infinity();
65  variable_bounds_[1].max_position_ = std::numeric_limits<double>::infinity();
66  variable_bounds_[2].min_position_ = -boost::math::constants::pi<double>();
67  variable_bounds_[2].max_position_ = boost::math::constants::pi<double>();
68 
70 }
71 
73 {
74  return 3;
75 }
76 
78 {
79  double dx = other_bounds[0].max_position_ - other_bounds[0].min_position_;
80  double dy = other_bounds[1].max_position_ - other_bounds[1].min_position_;
81  return sqrt(dx * dx + dy * dy) + boost::math::constants::pi<double>() * angular_distance_weight_;
82 }
83 
85 {
86  for (unsigned int i = 0; i < 2; ++i)
87  {
88  // if zero is a valid value
89  if (bounds[i].min_position_ <= 0.0 && bounds[i].max_position_ >= 0.0)
90  values[i] = 0.0;
91  else
92  values[i] = (bounds[i].min_position_ + bounds[i].max_position_) / 2.0;
93  }
94  values[2] = 0.0;
95 }
96 
98  double* values, const Bounds& bounds) const
99 {
100  if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
101  bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
102  values[0] = 0.0;
103  else
104  values[0] = rng.uniformReal(bounds[0].min_position_, bounds[0].max_position_);
105  if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
106  bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
107  values[1] = 0.0;
108  else
109  values[1] = rng.uniformReal(bounds[1].min_position_, bounds[1].max_position_);
110  values[2] = rng.uniformReal(bounds[2].min_position_, bounds[2].max_position_);
111 }
112 
114  double* values, const Bounds& bounds,
115  const double* near, const double distance) const
116 {
117  if (bounds[0].max_position_ >= std::numeric_limits<double>::infinity() ||
118  bounds[0].min_position_ <= -std::numeric_limits<double>::infinity())
119  values[0] = 0.0;
120  else
121  values[0] = rng.uniformReal(std::max(bounds[0].min_position_, near[0] - distance),
122  std::min(bounds[0].max_position_, near[0] + distance));
123  if (bounds[1].max_position_ >= std::numeric_limits<double>::infinity() ||
124  bounds[1].min_position_ <= -std::numeric_limits<double>::infinity())
125  values[1] = 0.0;
126  else
127  values[1] = rng.uniformReal(std::max(bounds[1].min_position_, near[1] - distance),
128  std::min(bounds[1].max_position_, near[1] + distance));
129 
130  double da = angular_distance_weight_ * distance;
131  // limit the sampling range to 2pi to work correctly even if the distance is very large
132  if (da > boost::math::constants::pi<double>())
133  da = boost::math::constants::pi<double>();
134  values[2] = rng.uniformReal(near[2] - da, near[2] + da);
135  normalizeRotation(values);
136 }
137 
138 void moveit::core::PlanarJointModel::interpolate(const double* from, const double* to, const double t,
139  double* state) const
140 {
141  // interpolate position
142  state[0] = from[0] + (to[0] - from[0]) * t;
143  state[1] = from[1] + (to[1] - from[1]) * t;
144 
145  // interpolate angle
146  double diff = to[2] - from[2];
147  if (fabs(diff) <= boost::math::constants::pi<double>())
148  state[2] = from[2] + diff * t;
149  else
150  {
151  if (diff > 0.0)
152  diff = 2.0 * boost::math::constants::pi<double>() - diff;
153  else
154  diff = -2.0 * boost::math::constants::pi<double>() - diff;
155  state[2] = from[2] - diff * t;
156  // input states are within bounds, so the following check is sufficient
157  if (state[2] > boost::math::constants::pi<double>())
158  state[2] -= 2.0 * boost::math::constants::pi<double>();
159  else if (state[2] < -boost::math::constants::pi<double>())
160  state[2] += 2.0 * boost::math::constants::pi<double>();
161  }
162 }
163 
164 double moveit::core::PlanarJointModel::distance(const double* values1, const double* values2) const
165 {
166  double dx = values1[0] - values2[0];
167  double dy = values1[1] - values2[1];
168 
169  double d = fabs(values1[2] - values2[2]);
170  d = (d > boost::math::constants::pi<double>()) ? 2.0 * boost::math::constants::pi<double>() - d : d;
171  return sqrt(dx * dx + dy * dy) + angular_distance_weight_ * d;
172 }
173 
174 bool moveit::core::PlanarJointModel::satisfiesPositionBounds(const double* values, const Bounds& bounds,
175  double margin) const
176 {
177  for (unsigned int i = 0; i < 3; ++i)
178  if (values[0] < bounds[0].min_position_ - margin || values[0] > bounds[0].max_position_ + margin)
179  return false;
180  return true;
181 }
182 
184 {
185  double& v = values[2];
186  if (v >= -boost::math::constants::pi<double>() && v <= boost::math::constants::pi<double>())
187  return false;
188  v = fmod(v, 2.0 * boost::math::constants::pi<double>());
189  if (v < -boost::math::constants::pi<double>())
190  v += 2.0 * boost::math::constants::pi<double>();
191  else if (v > boost::math::constants::pi<double>())
192  v -= 2.0 * boost::math::constants::pi<double>();
193  return true;
194 }
195 
196 bool moveit::core::PlanarJointModel::enforcePositionBounds(double* values, const Bounds& bounds) const
197 {
198  bool result = normalizeRotation(values);
199  for (unsigned int i = 0; i < 2; ++i)
200  {
201  if (values[i] < bounds[i].min_position_)
202  {
203  values[i] = bounds[i].min_position_;
204  result = true;
205  }
206  else if (values[i] > bounds[i].max_position_)
207  {
208  values[i] = bounds[i].max_position_;
209  result = true;
210  }
211  }
212  return result;
213 }
214 
215 void moveit::core::PlanarJointModel::computeTransform(const double* joint_values, Eigen::Affine3d& transf) const
216 {
217  transf = Eigen::Affine3d(Eigen::Translation3d(joint_values[0], joint_values[1], 0.0) *
218  Eigen::AngleAxisd(joint_values[2], Eigen::Vector3d::UnitZ()));
219 }
220 
221 void moveit::core::PlanarJointModel::computeVariablePositions(const Eigen::Affine3d& transf, double* joint_values) const
222 {
223  joint_values[0] = transf.translation().x();
224  joint_values[1] = transf.translation().y();
225 
226  Eigen::Quaterniond q(transf.rotation());
227  // taken from Bullet
228  double s_squared = 1.0 - (q.w() * q.w());
229  if (s_squared < 10.0 * std::numeric_limits<double>::epsilon())
230  joint_values[2] = 0.0;
231  else
232  {
233  double s = 1.0 / sqrt(s_squared);
234  joint_values[2] = (acos(q.w()) * 2.0f) * (q.z() * s);
235  }
236 }
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 ...
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 Mon Jan 15 2018 03:50:44