All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends
SO3StateSpace.cpp
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2010, Rice University
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Rice University nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #include "ompl/base/spaces/SO3StateSpace.h"
38 #include <algorithm>
39 #include <limits>
40 #include <cmath>
41 #include "ompl/tools/config/MagicConstants.h"
42 #include <boost/math/constants/constants.hpp>
43 #include <boost/version.hpp>
44 #include <boost/assert.hpp>
45 
46 #ifndef BOOST_ASSERT_MSG
47 #define BOOST_ASSERT_MSG(expr, msg) assert(expr)
48 #endif
49 
50 #if BOOST_VERSION < 105000
51 namespace boost{ namespace math{ namespace constants{
52 BOOST_DEFINE_MATH_CONSTANT(root_three, 1.732050807568877293527446341505872366, 1.73205080756887729352744634150587236694280525381038062805580697945193301690880003708114618675724857567562614142, 0)
53 }}}
54 #endif
55 
56 static const double MAX_QUATERNION_NORM_ERROR = 1e-9;
57 
59 namespace ompl
60 {
61  namespace base
62  {
63  static inline void computeAxisAngle(SO3StateSpace::StateType &q, double ax, double ay, double az, double angle)
64  {
65  double norm = sqrt(ax * ax + ay * ay + az * az);
66  if (norm < MAX_QUATERNION_NORM_ERROR)
67  q.setIdentity();
68  else
69  {
70  double s = sin(angle / 2.0);
71  q.x = s * ax / norm;
72  q.y = s * ay / norm;
73  q.z = s * az / norm;
74  q.w = cos(angle / 2.0);
75  }
76  }
77 
78  /* Standard quaternion multiplication: q = q0 * q1 */
79  static inline void quaternionProduct(SO3StateSpace::StateType &q, const SO3StateSpace::StateType& q0, const SO3StateSpace::StateType& q1)
80  {
81  q.x = q0.w*q1.x + q0.x*q1.w + q0.y*q1.z - q0.z*q1.y;
82  q.y = q0.w*q1.y + q0.y*q1.w + q0.z*q1.x - q0.x*q1.z;
83  q.z = q0.w*q1.z + q0.z*q1.w + q0.x*q1.y - q0.y*q1.x;
84  q.w = q0.w*q1.w - q0.x*q1.x - q0.y*q1.y - q0.z*q1.z;
85  }
86  }
87 }
89 
90 void ompl::base::SO3StateSpace::StateType::setAxisAngle(double ax, double ay, double az, double angle)
91 {
92  computeAxisAngle(*this, ax, ay, az, angle);
93 }
94 
96 {
97  x = y = z = 0.0;
98  w = 1.0;
99 }
100 
102 {
103  rng_.quaternion(&state->as<SO3StateSpace::StateType>()->x);
104 }
105 
107 {
108  if (distance >= .25 * boost::math::constants::pi<double>())
109  {
110  sampleUniform(state);
111  return;
112  }
113  double d = rng_.uniform01();
115  *qs = static_cast<SO3StateSpace::StateType*>(state);
116  const SO3StateSpace::StateType *qnear = static_cast<const SO3StateSpace::StateType*>(near);
117  computeAxisAngle(q, rng_.gaussian01(), rng_.gaussian01(), rng_.gaussian01(),
118  2. * pow(d, boost::math::constants::third<double>()) * distance);
119  quaternionProduct(*qs, *qnear, q);
120 }
121 
122 void ompl::base::SO3StateSampler::sampleGaussian(State *state, const State * mean, const double stdDev)
123 {
124  // The standard deviation of the individual components of the tangent
125  // perturbation needs to be scaled so that the expected quaternion distance
126  // between the sampled state and the mean state is stdDev. The factor 2 is
127  // due to the way we define distance (see also Matt Mason's lecture notes
128  // on quaternions at
129  // http://www.cs.cmu.edu/afs/cs/academic/class/16741-s07/www/lecture7.pdf).
130  // The 1/sqrt(3) factor is necessary because the distribution in the tangent
131  // space is a 3-dimensional Gaussian, so that the *length* of a tangent
132  // vector needs to be scaled by 1/sqrt(3).
133  double rotDev = (2. * stdDev) / boost::math::constants::root_three<double>();
134 
135  // CDF of N(0, 1.17) at -pi/4 is approx. .25, so there's .25 probability
136  // weight in each tail. Since the maximum distance in SO(3) is pi/2, we're
137  // essentially as likely to sample a state within distance [0, pi/4] as
138  // within distance [pi/4, pi/2]. With most weight in the tails (that wrap
139  // around in case of quaternions) we might as well sample uniformly.
140  if (rotDev > 1.17)
141  {
142  sampleUniform(state);
143  return;
144  }
145 
146 
147  double x = rng_.gaussian(0, rotDev), y = rng_.gaussian(0, rotDev), z = rng_.gaussian(0, rotDev),
148  theta = std::sqrt(x*x + y*y + z*z);
149  if (theta < std::numeric_limits<double>::epsilon())
150  space_->copyState(state, mean);
151  else
152  {
154  *qs = static_cast<SO3StateSpace::StateType*>(state);
155  const SO3StateSpace::StateType *qmu = static_cast<const SO3StateSpace::StateType*>(mean);
156  double s = sin(theta / 2) / theta;
157  q.w = cos(theta / 2);
158  q.x = s * x;
159  q.y = s * y;
160  q.z = s * z;
161  quaternionProduct(*qs, *qmu, q);
162  }
163 }
164 
166 {
167  return 3;
168 }
169 
171 {
172  return .5 * boost::math::constants::pi<double>();
173 }
174 
175 double ompl::base::SO3StateSpace::norm(const StateType *state) const
176 {
177  double nrmSqr = state->x * state->x + state->y * state->y + state->z * state->z + state->w * state->w;
178  return (fabs(nrmSqr - 1.0) > std::numeric_limits<double>::epsilon()) ? sqrt(nrmSqr) : 1.0;
179 }
180 
182 {
183  StateType *qstate = static_cast<StateType*>(state);
184  double nrm = norm(qstate);
185  if (fabs(nrm) < MAX_QUATERNION_NORM_ERROR)
186  qstate->setIdentity();
187  else if (fabs(nrm - 1.0) > MAX_QUATERNION_NORM_ERROR)
188  {
189  qstate->x /= nrm;
190  qstate->y /= nrm;
191  qstate->z /= nrm;
192  qstate->w /= nrm;
193  }
194 }
195 
197 {
198  return fabs(norm(static_cast<const StateType*>(state)) - 1.0) < MAX_QUATERNION_NORM_ERROR;
199 }
200 
201 void ompl::base::SO3StateSpace::copyState(State *destination, const State *source) const
202 {
203  const StateType *qsource = static_cast<const StateType*>(source);
204  StateType *qdestination = static_cast<StateType*>(destination);
205  qdestination->x = qsource->x;
206  qdestination->y = qsource->y;
207  qdestination->z = qsource->z;
208  qdestination->w = qsource->w;
209 }
210 
212 {
213  return sizeof(double) * 4;
214 }
215 
216 void ompl::base::SO3StateSpace::serialize(void *serialization, const State *state) const
217 {
218  memcpy(serialization, &state->as<StateType>()->x, sizeof(double) * 4);
219 }
220 
221 void ompl::base::SO3StateSpace::deserialize(State *state, const void *serialization) const
222 {
223  memcpy(&state->as<StateType>()->x, serialization, sizeof(double) * 4);
224 }
225 
227 
228 /*
229 Based on code from :
230 
231 Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
232 */
233 namespace ompl
234 {
235  namespace base
236  {
237  static inline double arcLength(const State *state1, const State *state2)
238  {
239  const SO3StateSpace::StateType *qs1 = static_cast<const SO3StateSpace::StateType*>(state1);
240  const SO3StateSpace::StateType *qs2 = static_cast<const SO3StateSpace::StateType*>(state2);
241  double dq = fabs(qs1->x * qs2->x + qs1->y * qs2->y + qs1->z * qs2->z + qs1->w * qs2->w);
242  if (dq > 1.0 - MAX_QUATERNION_NORM_ERROR)
243  return 0.0;
244  else
245  return acos(dq);
246  }
247  }
248 }
250 
251 double ompl::base::SO3StateSpace::distance(const State *state1, const State *state2) const
252 {
253  BOOST_ASSERT_MSG(satisfiesBounds(state1) && satisfiesBounds(state2),
254  "The states passed to SO3StateSpace::distance are not within bounds. Call "
255  "SO3StateSpace::enforceBounds() in, e.g., ompl::control::ODESolver::PostPropagationEvent, "
256  "ompl::control::StatePropagator, or ompl::base::StateValidityChecker");
257  return arcLength(state1, state2);
258 }
259 
260 bool ompl::base::SO3StateSpace::equalStates(const State *state1, const State *state2) const
261 {
262  return arcLength(state1, state2) < std::numeric_limits<double>::epsilon();
263 }
264 
265 /*
266 Based on code from :
267 
268 Copyright (c) 2003-2006 Gino van den Bergen / Erwin Coumans http://continuousphysics.com/Bullet/
269 */
270 void ompl::base::SO3StateSpace::interpolate(const State *from, const State *to, const double t, State *state) const
271 {
272  assert(fabs(norm(static_cast<const StateType*>(from)) - 1.0) < MAX_QUATERNION_NORM_ERROR);
273  assert(fabs(norm(static_cast<const StateType*>(to)) - 1.0) < MAX_QUATERNION_NORM_ERROR);
274 
275  double theta = arcLength(from, to);
276  if (theta > std::numeric_limits<double>::epsilon())
277  {
278  double d = 1.0 / sin(theta);
279  double s0 = sin((1.0 - t) * theta);
280  double s1 = sin(t * theta);
281 
282  const StateType *qs1 = static_cast<const StateType*>(from);
283  const StateType *qs2 = static_cast<const StateType*>(to);
284  StateType *qr = static_cast<StateType*>(state);
285  double dq = qs1->x * qs2->x + qs1->y * qs2->y + qs1->z * qs2->z + qs1->w * qs2->w;
286  if (dq < 0) // Take care of long angle case see http://en.wikipedia.org/wiki/Slerp
287  s1 = -s1;
288 
289  qr->x = (qs1->x * s0 + qs2->x * s1) * d;
290  qr->y = (qs1->y * s0 + qs2->y * s1) * d;
291  qr->z = (qs1->z * s0 + qs2->z * s1) * d;
292  qr->w = (qs1->w * s0 + qs2->w * s1) * d;
293  }
294  else
295  {
296  if (state != from)
297  copyState(state, from);
298  }
299 }
300 
302 {
303  return StateSamplerPtr(new SO3StateSampler(this));
304 }
305 
307 {
308  return new StateType();
309 }
310 
312 {
313  delete static_cast<StateType*>(state);
314 }
315 
317 {
318  class SO3DefaultProjection : public ProjectionEvaluator
319  {
320  public:
321 
322  SO3DefaultProjection(const StateSpace *space) : ProjectionEvaluator(space)
323  {
324  }
325 
326  virtual unsigned int getDimension(void) const
327  {
328  return 3;
329  }
330 
331  virtual void defaultCellSizes(void)
332  {
333  cellSizes_.resize(3);
334  cellSizes_[0] = boost::math::constants::pi<double>() / magic::PROJECTION_DIMENSION_SPLITS;
335  cellSizes_[1] = boost::math::constants::pi<double>() / magic::PROJECTION_DIMENSION_SPLITS;
336  cellSizes_[2] = boost::math::constants::pi<double>() / magic::PROJECTION_DIMENSION_SPLITS;
337  bounds_.resize(3);
338  bounds_.setLow(-1.0);
339  bounds_.setHigh(1.0);
340  }
341 
342  virtual void project(const State *state, EuclideanProjection &projection) const
343  {
344  projection(0) = state->as<SO3StateSpace::StateType>()->x;
345  projection(1) = state->as<SO3StateSpace::StateType>()->y;
346  projection(2) = state->as<SO3StateSpace::StateType>()->z;
347  }
348  };
349 
350  registerDefaultProjection(ProjectionEvaluatorPtr(dynamic_cast<ProjectionEvaluator*>(new SO3DefaultProjection(this))));
351 }
352 
353 double* ompl::base::SO3StateSpace::getValueAddressAtIndex(State *state, const unsigned int index) const
354 {
355  return index < 4 ? &(state->as<StateType>()->x) + index : NULL;
356 }
357 
358 void ompl::base::SO3StateSpace::printState(const State *state, std::ostream &out) const
359 {
360  out << "SO3State [";
361  if (state)
362  {
363  const StateType *qstate = static_cast<const StateType*>(state);
364  out << qstate->x << " " << qstate->y << " " << qstate->z << " " << qstate->w;
365  }
366  else
367  out << "NULL";
368  out << ']' << std::endl;
369 }
370 
371 void ompl::base::SO3StateSpace::printSettings(std::ostream &out) const
372 {
373  out << "SO(3) state space '" << getName() << "' (represented using quaternions)" << std::endl;
374 }
virtual void serialize(void *serialization, const State *state) const
Write the binary representation of state to serialization.
virtual double * getValueAddressAtIndex(State *state, const unsigned int index) const
Many states contain a number of double values. This function provides a means to get the memory addre...
virtual double getMaximumExtent(void) const
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...
virtual State * allocState(void) const
Allocate a state that can store a point in the described space.
virtual bool satisfiesBounds(const State *state) const
Check if a state is inside the bounding box. For unbounded spaces this function can always return tru...
virtual void printState(const State *state, std::ostream &out) const
Print a state to a stream.
A boost shared pointer wrapper for ompl::base::StateSampler.
virtual unsigned int getDimension(void) const
Get the dimension of the space (not the dimension of the surrounding ambient space) ...
virtual double distance(const State *state1, const State *state2) const
Computes distance between two states. This function satisfies the properties of a metric if isMetricS...
virtual void printSettings(std::ostream &out) const
Print the settings for this state space to a stream.
virtual bool equalStates(const State *state1, const State *state2) const
Checks whether two states are equal.
void registerDefaultProjection(const ProjectionEvaluatorPtr &projection)
Register the default projection for this state space.
Definition: StateSpace.cpp:726
virtual void enforceBounds(State *state) const
Bring the state within the bounds of the state space. For unbounded spaces this function can be a no-...
State StateType
Define the type of state allocated by this space.
Definition: StateSpace.h:78
const T * as(void) const
Cast this instance to a desired type.
Definition: State.h:74
double w
scalar component of quaternion
virtual void deserialize(State *state, const void *serialization) const
Read the binary representation of a state from serialization and write it to state.
virtual StateSamplerPtr allocDefaultStateSampler(void) const
Allocate an instance of the default uniform state sampler for this space.
virtual void interpolate(const State *from, const State *to, const double t, State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
virtual void freeState(State *state) const
Free the memory of the allocated state.
The definition of a state in SO(3) represented as a unit quaternion.
Definition: SO3StateSpace.h:94
const std::string & getName(void) const
Get the name of the state space.
Definition: StateSpace.cpp:187
State space sampler for SO(3), using quaternion representation.
Definition: SO3StateSpace.h:48
A boost shared pointer wrapper for ompl::base::ProjectionEvaluator.
static const double PROJECTION_DIMENSION_SPLITS
When the cell sizes for a projection are automatically computed, this value defines the number of par...
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.
Definition: StateSpace.h:73
virtual void copyState(State *destination, const State *source) const
Copy a state to another. The memory of source and destination should NOT overlap. ...
boost::numeric::ublas::vector< double > EuclideanProjection
The datatype for state projections. This class contains a real vector.
virtual void registerProjections(void)
Register the projections for this state space. Usually, this is at least the default projection...
Definition of an abstract state.
Definition: State.h:50
void setAxisAngle(double ax, double ay, double az, double angle)
Set the quaternion from axis-angle representation.
virtual void sampleUniform(State *state)
Sample a state.
void setIdentity(void)
Set the state to identity – no rotation.
double z
Z component of quaternion vector.
virtual void sampleUniformNear(State *state, const State *near, const double distance)
To sample unit quaternions uniformly within some given distance, we sample a 3-vector from the R^3 ta...
double y
Y component of quaternion vector.
double norm(const StateType *state) const
Compute the norm of a state.
virtual unsigned int getSerializationLength(void) const
Get the number of chars in the serialization of a state in this space.
virtual void sampleGaussian(State *state, const State *mean, const double stdDev)
Sample a state such that the expected distance between mean and state is stdDev.
double x
X component of quaternion vector.
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...