RealVectorStateProjections.cpp
58 const StateSpace *space, const std::vector<double> &cellSizes, const ProjectionMatrix::Matrix &projection)
67 const StateSpacePtr &space, const std::vector<double> &cellSizes, const ProjectionMatrix::Matrix &projection)
92 const StateSpace *space, const std::vector<double> &cellSizes, std::vector<unsigned int> components)
101 const StateSpacePtr &space, const std::vector<double> &cellSizes, std::vector<unsigned int> components)
179 ompl::base::RealVectorIdentityProjectionEvaluator::RealVectorIdentityProjectionEvaluator(const StateSpace *space)
194 ompl::base::RealVectorIdentityProjectionEvaluator::RealVectorIdentityProjectionEvaluator(const StateSpacePtr &space)
227 projection = Eigen::Map<const Eigen::VectorXd>(state->as<RealVectorStateSpace::StateType>()->values, copySize_);
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.
Definition: RealVectorStateProjections.cpp:147
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 ...
Definition: ProjectionEvaluator.cpp:129
void project(const State *state, Eigen::Ref< Eigen::VectorXd > projection) const override
Compute the projection as an array of double values.
Definition: RealVectorStateProjections.cpp:224
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...
Definition: RealVectorStateProjections.cpp:57
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
Definition: RealVectorStateProjections.cpp:219
void project(const State *state, Eigen::Ref< Eigen::VectorXd > projection) const override
Compute the projection as an array of double values.
Definition: RealVectorStateProjections.cpp:152
void defaultCellSizes() override
Set the default cell dimensions for this projection. The default implementation of this function is e...
Definition: RealVectorStateProjections.cpp:205
A state space representing Rn. The distance function is the L2 norm.
Definition: RealVectorStateSpace.h:137
The definition of a state in Rn
Definition: RealVectorStateSpace.h:141
Abstract definition for a class computing projections to Rn. Implicit integer grids are imposed on th...
Definition: ProjectionEvaluator.h:194
static const double PROJECTION_DIMENSION_SPLITS
When the cell sizes for a projection are automatically computed, this value defines the number of par...
Definition: MagicConstants.h:119
unsigned int getDimension() const override
Return the dimension of the projection defined by this evaluator.
Definition: RealVectorStateProjections.cpp:158
void setup() override
Perform configuration steps, if needed.
Definition: RealVectorStateProjections.cpp:213
void project(const State *state, Eigen::Ref< Eigen::VectorXd > projection) const override
Compute the projection as an array of double values.
Definition: RealVectorStateProjections.cpp:163
void defaultCellSizes() override
Set the default cell dimensions for this projection. The default implementation of this function is e...
Definition: RealVectorStateProjections.cpp:134
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...
Definition: RealVectorStateProjections.cpp:91
const StateSpace * space_
The state space this projection operates on.
Definition: ProjectionEvaluator.h:330
void copyBounds()
Fill bounds_ with bounds from the state space.
Definition: RealVectorStateProjections.cpp:123
RealVectorIdentityProjectionEvaluator(const StateSpace *space, const std::vector< double > &cellSizes)
Initialize the identity projection evaluator for state space space. The indices of the kept component...
Definition: RealVectorStateProjections.cpp:170
Main namespace. Contains everything in this library.
Definition: MultiLevelPlanarManipulatorDemo.cpp:65
The lower and upper bounds for an Rn space.
Definition: RealVectorBounds.h:111