RealVectorStateProjections.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/RealVectorStateProjections.h"
38 #include "ompl/util/Exception.h"
39 #include "ompl/tools/config/MagicConstants.h"
40 #include <cstring>
41 #include <utility>
42 
44 namespace ompl
45 {
46  namespace base
47  {
48  static inline void checkSpaceType(const StateSpace *m)
49  {
50  if (dynamic_cast<const RealVectorStateSpace *>(m) == nullptr)
51  throw Exception("Expected real vector state space for projection");
52  }
53  }
54 }
56 
58  const StateSpace *space, const std::vector<double> &cellSizes, const ProjectionMatrix::Matrix &projection)
59  : ProjectionEvaluator(space)
60 {
61  checkSpaceType(space_);
62  projection_.mat = projection;
63  setCellSizes(cellSizes);
64 }
65 
67  const StateSpacePtr &space, const std::vector<double> &cellSizes, const ProjectionMatrix::Matrix &projection)
68  : ProjectionEvaluator(space)
69 {
70  checkSpaceType(space_);
71  projection_.mat = projection;
72  setCellSizes(cellSizes);
73 }
74 
76  const StateSpace *space, const ProjectionMatrix::Matrix &projection)
77  : ProjectionEvaluator(space)
78 {
79  checkSpaceType(space_);
80  projection_.mat = projection;
81 }
82 
84  const StateSpacePtr &space, const ProjectionMatrix::Matrix &projection)
85  : ProjectionEvaluator(space)
86 {
87  checkSpaceType(space_);
88  projection_.mat = projection;
89 }
90 
92  const StateSpace *space, const std::vector<double> &cellSizes, std::vector<unsigned int> components)
93  : ProjectionEvaluator(space), components_(std::move(components))
94 {
95  checkSpaceType(space_);
96  setCellSizes(cellSizes);
97  copyBounds();
98 }
99 
101  const StateSpacePtr &space, const std::vector<double> &cellSizes, std::vector<unsigned int> components)
102  : ProjectionEvaluator(space), components_(std::move(components))
103 {
104  checkSpaceType(space_);
105  setCellSizes(cellSizes);
106  copyBounds();
107 }
108 
110  const StateSpace *space, std::vector<unsigned int> components)
111  : ProjectionEvaluator(space), components_(std::move(components))
112 {
113  checkSpaceType(space_);
114 }
115 
117  const StateSpacePtr &space, std::vector<unsigned int> components)
118  : ProjectionEvaluator(space), components_(std::move(components))
119 {
120  checkSpaceType(space_);
121 }
122 
124 {
125  bounds_.resize(components_.size());
126  const RealVectorBounds &bounds = space_->as<RealVectorStateSpace>()->getBounds();
127  for (unsigned int i = 0; i < components_.size(); ++i)
128  {
129  bounds_.low[i] = bounds.low[components_[i]];
130  bounds_.high[i] = bounds.high[components_[i]];
131  }
132 }
133 
135 {
136  const RealVectorBounds &bounds = space_->as<RealVectorStateSpace>()->getBounds();
137  bounds_.resize(components_.size());
138  cellSizes_.resize(components_.size());
139  for (unsigned int i = 0; i < cellSizes_.size(); ++i)
140  {
141  bounds_.low[i] = bounds.low[components_[i]];
142  bounds_.high[i] = bounds.high[components_[i]];
143  cellSizes_[i] = (bounds_.high[i] - bounds_.low[i]) / magic::PROJECTION_DIMENSION_SPLITS;
144  }
145 }
146 
148 {
149  return projection_.mat.size1();
150 }
151 
153 {
154  projection_.project(state->as<RealVectorStateSpace::StateType>()->values, projection);
155 }
156 
158 {
159  return components_.size();
160 }
161 
163  EuclideanProjection &projection) const
164 {
165  for (unsigned int i = 0; i < components_.size(); ++i)
166  projection(i) = state->as<RealVectorStateSpace::StateType>()->values[components_[i]];
167 }
168 
170  const StateSpace *space, const std::vector<double> &cellSizes)
171  : ProjectionEvaluator(space)
172 {
173  checkSpaceType(space_);
174  setCellSizes(cellSizes);
175  copyBounds();
176 }
177 
179  : ProjectionEvaluator(space)
180 {
181  checkSpaceType(space_);
182 }
183 
185  const StateSpacePtr &space, const std::vector<double> &cellSizes)
186  : ProjectionEvaluator(space)
187 {
188  checkSpaceType(space_);
189  setCellSizes(cellSizes);
190  copyBounds();
191 }
192 
194  : ProjectionEvaluator(space)
195 {
196  checkSpaceType(space_);
197 }
198 
199 void ompl::base::RealVectorIdentityProjectionEvaluator::copyBounds()
200 {
201  bounds_ = space_->as<RealVectorStateSpace>()->getBounds();
202 }
203 
205 {
206  bounds_ = space_->as<RealVectorStateSpace>()->getBounds();
207  cellSizes_.resize(getDimension());
208  for (unsigned int i = 0; i < cellSizes_.size(); ++i)
209  cellSizes_[i] = (bounds_.high[i] - bounds_.low[i]) / magic::PROJECTION_DIMENSION_SPLITS;
210 }
211 
213 {
214  copySize_ = getDimension() * sizeof(double);
216 }
217 
219 {
220  return space_->getDimension();
221 }
222 
224  EuclideanProjection &projection) const
225 {
226  memcpy(&projection(0), state->as<RealVectorStateSpace::StateType>()->values, copySize_);
227 }
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
std::vector< double > low
Lower bound.
RealVectorIdentityProjectionEvaluator(const StateSpace *space, const std::vector< double > &cellSizes)
Initialize the identity projection evaluator for state space space. The indices of the kept component...
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
A shared pointer wrapper for ompl::base::StateSpace.
STL namespace.
void copyBounds()
Fill bounds_ with bounds from the state space.
void setup() override
Perform configuration steps, if needed.
void defaultCellSizes() override
Set the default cell dimensions for this projection. The default implementation of this function is e...
ProjectionMatrix projection_
The projection matrix.
void project(const State *state, EuclideanProjection &projection) const override
Compute the projection as an array of double values.
const StateSpace * space_
The state space this projection operates on.
Main namespace. Contains everything in this library.
Definition: Cost.h:42
const T * as() const
Cast this instance to a desired type.
Definition: State.h:66
void defaultCellSizes() override
Set the default cell dimensions for this projection. The default implementation of this function is e...
Matrix mat
Projection matrix.
std::vector< double > high
Upper bound.
static const double PROJECTION_DIMENSION_SPLITS
When the cell sizes for a projection are automatically computed, this value defines the number of par...
A state space representing Rn. The distance function is the L2 norm.
Representation of a space in which planning can be performed. Topology specific sampling, interpolation and distance are defined.
Definition: StateSpace.h:70
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
boost::numeric::ublas::vector< double > EuclideanProjection
The datatype for state projections. This class contains a real vector.
Definition of an abstract state.
Definition: State.h:49
void project(const State *state, EuclideanProjection &projection) const override
Compute the projection as an array of double values.
void project(const State *state, EuclideanProjection &projection) const override
Compute the projection as an array of double values.
The lower and upper bounds for an Rn space.
double * values
The value of the actual vector in Rn
virtual void setCellSizes(const std::vector< double > &cellSizes)
Define the size (in each dimension) of a grid cell. The number of sizes set here must be the same as ...
RealVectorLinearProjectionEvaluator(const StateSpace *space, const std::vector< double > &cellSizes, const ProjectionMatrix::Matrix &projection)
Initialize a linear projection evaluator for state space space. The used projection matrix is project...
boost::numeric::ublas::matrix< double > Matrix
Datatype for projection matrices.
RealVectorOrthogonalProjectionEvaluator(const StateSpace *space, const std::vector< double > &cellSizes, std::vector< unsigned int > components)
Initialize an orthogonal projection evaluator for state space space. The indices of the kept componen...
virtual void setup()
Perform configuration steps, if needed.
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...