OpenDEStateSpace.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_EXTENSION_OPENDE_STATE_SPACE_
38 #define OMPL_EXTENSION_OPENDE_STATE_SPACE_
39 
40 #include "ompl/base/StateSpace.h"
41 #include "ompl/base/spaces/RealVectorStateSpace.h"
42 #include "ompl/base/spaces/SO3StateSpace.h"
43 #include "ompl/extensions/opende/OpenDEEnvironment.h"
44 
45 namespace ompl
46 {
47  namespace control
48  {
49 
52  {
53  public:
54 
55  enum
56  {
65  };
66 
69  {
70  public:
72  {
73  }
74 
76  const double* getBodyPosition(unsigned int body) const
77  {
78  return as<base::RealVectorStateSpace::StateType>(body * 4)->values;
79  }
80 
82  double* getBodyPosition(unsigned int body)
83  {
84  return as<base::RealVectorStateSpace::StateType>(body * 4)->values;
85  }
86 
88  const base::SO3StateSpace::StateType& getBodyRotation(unsigned int body) const
89  {
90  return *as<base::SO3StateSpace::StateType>(body * 4 + 3);
91  }
92 
95  {
96  return *as<base::SO3StateSpace::StateType>(body * 4 + 3);
97  }
98 
100  const double* getBodyLinearVelocity(unsigned int body) const
101  {
102  return as<base::RealVectorStateSpace::StateType>(body * 4 + 1)->values;
103  }
104 
106  double* getBodyLinearVelocity(unsigned int body)
107  {
108  return as<base::RealVectorStateSpace::StateType>(body * 4 + 1)->values;
109  }
110 
112  const double* getBodyAngularVelocity(unsigned int body) const
113  {
114  return as<base::RealVectorStateSpace::StateType>(body * 4 + 2)->values;
115  }
116 
118  double* getBodyAngularVelocity(unsigned int body)
119  {
120  return as<base::RealVectorStateSpace::StateType>(body * 4 + 2)->values;
121  }
122 
129  mutable int collision;
130 
131  };
132 
149  double positionWeight = 1.0, double linVelWeight = 0.5,
150  double angVelWeight = 0.5, double orientationWeight = 1.0);
151 
152  virtual ~OpenDEStateSpace()
153  {
154  }
155 
158  {
159  return env_;
160  }
161 
163  unsigned int getNrBodies() const
164  {
165  return env_->stateBodies_.size();
166  }
167 
173  void setDefaultBounds();
174 
176  void setVolumeBounds(const base::RealVectorBounds &bounds);
177 
180 
183 
186  virtual void readState(base::State *state) const;
187 
192  virtual void writeState(const base::State *state) const;
193 
201  bool satisfiesBoundsExceptRotation(const StateType *state) const;
202 
203  virtual base::State* allocState() const;
204  virtual void freeState(base::State *state) const;
205  virtual void copyState(base::State *destination, const base::State *source) const;
206  virtual void interpolate(const base::State *from, const base::State *to, const double t, base::State *state) const;
207 
210 
213  virtual bool evaluateCollision(const base::State *source) const;
214 
215  protected:
216 
219  };
220  }
221 }
222 
223 
224 #endif
Index of bit in StateType::collision indicating whether it is known if a state is in collision or not...
const double * getBodyPosition(unsigned int body) const
Get the position (x, y, z) of the body at index body.
Index of bit in StateType::collision indicating whether a state is valid or not. Initially the value ...
Definition of a compound state.
Definition: State.h:95
void setVolumeBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the position subspaces.
const double * getBodyAngularVelocity(unsigned int body) const
Get the angular velocity (x, y, z) of the body at index body.
double * getBodyLinearVelocity(unsigned int body)
Get the linear velocity (x, y, z) of the body at index body.
base::SO3StateSpace::StateType & getBodyRotation(unsigned int body)
Get the quaternion of the body at index body.
virtual void readState(base::State *state) const
Read the parameters of the OpenDE bodies and store them in state.
A boost shared pointer wrapper for ompl::base::StateSampler.
Index of bit in StateType::collision indicating whether a state is in collision or not...
void setAngularVelocityBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the angular velocity subspaces.
CompoundState StateType
Define the type of state allocated by this state space.
Definition: StateSpace.h:549
virtual void writeState(const base::State *state) const
Set the parameters of the OpenDE bodies to be the ones read from state. The code will technically wor...
const double * getBodyLinearVelocity(unsigned int body) const
Get the linear velocity (x, y, z) of the body at index body.
OpenDE State. This is a compound state that allows accessing the properties of the bodies the state s...
double * getBodyPosition(unsigned int body)
Get the position (x, y, z) of the body at index body.
virtual base::State * allocState() const
Allocate a state that can store a point in the described space.
bool satisfiesBoundsExceptRotation(const StateType *state) const
This is a convenience function provided for optimization purposes. It checks whether a state satisfie...
virtual bool evaluateCollision(const base::State *source) const
Fill the OpenDEStateSpace::STATE_COLLISION_VALUE_BIT of StateType::collision member of a state...
virtual base::StateSamplerPtr allocStateSampler() const
Allocate an instance of the state sampler for this space. This sampler will be allocated with the sam...
Main namespace. Contains everything in this library.
Definition: Cost.h:42
State space representing OpenDE states.
void setDefaultBounds()
By default, the volume bounds enclosing the geometry of the environment are computed to include all o...
A space to allow the composition of state spaces.
Definition: StateSpace.h:544
The definition of a state in SO(3) represented as a unit quaternion.
Definition: SO3StateSpace.h:94
OpenDEStateSpace(const OpenDEEnvironmentPtr &env, double positionWeight=1.0, double linVelWeight=0.5, double angVelWeight=0.5, double orientationWeight=1.0)
Construct a state space representing OpenDE states.
const OpenDEEnvironmentPtr & getEnvironment() const
Get the OpenDE environment this state space corresponds to.
virtual void copyState(base::State *destination, const base::State *source) const
Copy a state to another. The memory of source and destination should NOT overlap. ...
Index of bit in StateType::collision indicating whether it is known if a state is in valid or not...
Definition of an abstract state.
Definition: State.h:50
virtual base::StateSamplerPtr allocDefaultStateSampler() const
Allocate an instance of the default uniform state sampler for this space.
virtual void freeState(base::State *state) const
Free the memory of the allocated state.
virtual void interpolate(const base::State *from, const base::State *to, const double t, base::State *state) const
Computes the state that lies at time t in [0, 1] on the segment that connects from state to to state...
The lower and upper bounds for an Rn space.
unsigned int getNrBodies() const
Get the number of bodies state is maintained for.
void setLinearVelocityBounds(const base::RealVectorBounds &bounds)
Set the bounds for each of the linear velocity subspaces.
double * getBodyAngularVelocity(unsigned int body)
Get the angular velocity (x, y, z) of the body at index body.
const base::SO3StateSpace::StateType & getBodyRotation(unsigned int body) const
Get the quaternion of the body at index body.
int collision
Flag containing information about state validity.
A boost shared pointer wrapper for ompl::control::OpenDEEnvironment.
OpenDEEnvironmentPtr env_
Representation of the OpenDE parameters OMPL needs to plan.