SO3StateSpace.h
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 #ifndef OMPL_BASE_SPACES_SO3_STATE_SPACE_
38 #define OMPL_BASE_SPACES_SO3_STATE_SPACE_
39 
40 #include "ompl/base/StateSpace.h"
41 
42 namespace ompl
43 {
44  namespace base
45  {
46 
49  {
50  public:
51 
53  SO3StateSampler(const StateSpace *space) : StateSampler(space)
54  {
55  }
56 
57  virtual void sampleUniform(State *state);
66  virtual void sampleUniformNear(State *state, const State *near, const double distance);
77  virtual void sampleGaussian(State *state, const State *mean, const double stdDev);
78  };
79 
84  class SO3StateSpace : public StateSpace
85  {
86  public:
87 
88 
94  class StateType : public State
95  {
96  public:
97 
99  void setAxisAngle(double ax, double ay, double az, double angle);
100 
102  void setIdentity();
103 
105  double x;
106 
108  double y;
109 
111  double z;
112 
114  double w;
115  };
116 
118  {
119  setName("SO3" + getName());
121  }
122 
123  virtual ~SO3StateSpace()
124  {
125  }
126 
128  double norm(const StateType *state) const;
129 
130  virtual unsigned int getDimension() const;
131 
132  virtual double getMaximumExtent() const;
133 
134  virtual double getMeasure() const;
135 
136  virtual void enforceBounds(State *state) const;
137 
138  virtual bool satisfiesBounds(const State *state) const;
139 
140  virtual void copyState(State *destination, const State *source) const;
141 
142  virtual unsigned int getSerializationLength() const;
143 
144  virtual void serialize(void *serialization, const State *state) const;
145 
146  virtual void deserialize(State *state, const void *serialization) const;
147 
148  virtual double distance(const State *state1, const State *state2) const;
149 
150  virtual bool equalStates(const State *state1, const State *state2) const;
151 
152  virtual void interpolate(const State *from, const State *to, const double t, State *state) const;
153 
154  virtual StateSamplerPtr allocDefaultStateSampler() const;
155 
156  virtual State* allocState() const;
157 
158  virtual void freeState(State *state) const;
159 
160  virtual double* getValueAddressAtIndex(State *state, const unsigned int index) const;
161 
162  virtual void printState(const State *state, std::ostream &out) const;
163 
164  virtual void printSettings(std::ostream &out) const;
165 
166  virtual void registerProjections();
167  };
168  }
169 }
170 
171 #endif
void setName(const std::string &name)
Set the name of the state space.
Definition: StateSpace.cpp:203
virtual void serialize(void *serialization, const State *state) const
Write the binary representation of state to serialization.
int type_
A type assigned for this state space.
Definition: StateSpace.h:503
virtual unsigned int getSerializationLength() const
Get the number of chars in the serialization of a state in this space.
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...
ompl::base::SO3StateSpace
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.
virtual void registerProjections()
Register the projections for this state space. Usually, this is at least the default projection...
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...
A state space representing SO(3). The internal representation is done with quaternions. The distance between states is the angle between quaternions and interpolation is done with slerp.
Definition: SO3StateSpace.h:84
virtual void printSettings(std::ostream &out) const
Print the settings for this state space to a stream.
virtual State * allocState() const
Allocate a state that can store a point in the described space.
SO3StateSampler(const StateSpace *space)
Constructor.
Definition: SO3StateSpace.h:53
virtual double getMeasure() const
Get a measure of the space (this can be thought of as a generalization of volume) ...
virtual bool equalStates(const State *state1, const State *state2) const
Checks whether two states are equal.
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
double w
scalar component of quaternion
Main namespace. Contains everything in this library.
Definition: Cost.h:42
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() 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
void setIdentity()
Set the state to identity – no rotation.
State space sampler for SO(3), using quaternion representation.
Definition: SO3StateSpace.h:48
virtual unsigned int getDimension() const
Get the dimension of the space (not the dimension of the surrounding ambient space) ...
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. ...
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.
const std::string & getName() const
Get the name of the state space.
Definition: StateSpace.cpp:198
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...
Abstract definition of a state space sampler.
Definition: StateSampler.h:66
double y
Y component of quaternion vector.
double norm(const StateType *state) const
Compute the norm of a state.
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.
virtual double getMaximumExtent() const
Get the maximum value a call to distance() can return (or an upper bound). For unbounded state spaces...
double x
X component of quaternion vector.