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  } // namespace base
54 } // namespace ompl
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.rows();
150 }
151 
153  Eigen::Ref<Eigen::VectorXd> projection) const
154 {
155  projection_.project(state->as<RealVectorStateSpace::StateType>()->values, projection);
156 }
157 
159 {
160  return components_.size();
161 }
162 
164  Eigen::Ref<Eigen::VectorXd> projection) const
165 {
166  for (unsigned int i = 0; i < components_.size(); ++i)
167  projection(i) = state->as<RealVectorStateSpace::StateType>()->values[components_[i]];
168 }
169 
171  const StateSpace *space, const std::vector<double> &cellSizes)
172  : ProjectionEvaluator(space)
173 {
174  checkSpaceType(space_);
175  setCellSizes(cellSizes);
176  copyBounds();
177 }
178 
180  : ProjectionEvaluator(space)
181 {
182  checkSpaceType(space_);
183 }
184 
186  const StateSpacePtr &space, const std::vector<double> &cellSizes)
187  : ProjectionEvaluator(space)
188 {
189  checkSpaceType(space_);
190  setCellSizes(cellSizes);
191  copyBounds();
192 }
193 
195  : ProjectionEvaluator(space)
196 {
197  checkSpaceType(space_);
198 }
199 
200 void ompl::base::RealVectorIdentityProjectionEvaluator::copyBounds()
201 {
202  bounds_ = space_->as<RealVectorStateSpace>()->getBounds();
203 }
204 
206 {
207  bounds_ = space_->as<RealVectorStateSpace>()->getBounds();
208  cellSizes_.resize(getDimension());
209  for (unsigned int i = 0; i < cellSizes_.size(); ++i)
210  cellSizes_[i] = (bounds_.high[i] - bounds_.low[i]) / magic::PROJECTION_DIMENSION_SPLITS;
211 }
212 
214 {
215  copySize_ = getDimension();
217 }
218 
220 {
221  return space_->getDimension();
222 }
223 
225  Eigen::Ref<Eigen::VectorXd> projection) const
226 {
227  projection = Eigen::Map<const Eigen::VectorXd>(state->as<RealVectorStateSpace::StateType>()->values, copySize_);
228 }
Representation of a space in which planning can be performed. Topology specific sampling,...
Definition: StateSpace.h:134
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
ProjectionMatrix projection_
The projection matrix.
Definition of an abstract state.
Definition: State.h:113
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 ...
Eigen::MatrixXd Matrix
Datatype for projection matrices.
double * values
The value of the actual vector in Rn
void project(const State *state, Eigen::Ref< Eigen::VectorXd > projection) const override
Compute the projection as an array of double values.
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...
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
void project(const State *state, Eigen::Ref< Eigen::VectorXd > projection) const override
Compute the projection as an array of double values.
const T * as() const
Cast this instance to a desired type.
Definition: State.h:162
void defaultCellSizes() override
Set the default cell dimensions for this projection. The default implementation of this function is e...
A state space representing Rn. The distance function is the L2 norm.
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...
virtual void setup()
Perform configuration steps, if needed.
static const double PROJECTION_DIMENSION_SPLITS
When the cell sizes for a projection are automatically computed, this value defines the number of par...
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
void setup() override
Perform configuration steps, if needed.
void project(const State *state, Eigen::Ref< Eigen::VectorXd > projection) const override
Compute the projection as an array of double values.
void defaultCellSizes() override
Set the default cell dimensions for this projection. The default implementation of this function is e...
A shared pointer wrapper for ompl::base::StateSpace.
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...
const StateSpace * space_
The state space this projection operates on.
void copyBounds()
Fill bounds_ with bounds from the state space.
RealVectorIdentityProjectionEvaluator(const StateSpace *space, const std::vector< double > &cellSizes)
Initialize the identity projection evaluator for state space space. The indices of the kept component...
Matrix mat
Projection matrix.
Main namespace. Contains everything in this library.
The lower and upper bounds for an Rn space.