Loading...
Searching...
No Matches
VectorFieldConservative.cpp
61 const ob::RealVectorStateSpace::StateType &x = *state->as<ob::RealVectorStateSpace::StateType>();
103 ss->setOptimizationObjective(std::make_shared<ob::VFMechanicalWorkOptimizationObjective>(si, field));
108 ss->setOptimizationObjective(std::make_shared<ob::VFUpstreamCriterionOptimizationObjective>(si, field));
117 std::make_shared<og::VFRRT>(ss->getSpaceInformation(), field, explorationSetting, lambda, update_freq));
169 std::make_shared<ob::VFUpstreamCriterionOptimizationObjective>(ss->getSpaceInformation(), field));
The lower and upper bounds for an Rn space.
Definition RealVectorBounds.h:48
The definition of a state in Rn.
Definition RealVectorStateSpace.h:78
void interpolate(unsigned int count)
Insert a number of states in a path so that the path is made up of exactly count states....
Definition PathGeometric.cpp:348
virtual void printAsMatrix(std::ostream &out) const
Print the path as a real-valued matrix where the i-th row represents the i-th state along the path....
Definition PathGeometric.cpp:199
base::Cost cost(const base::OptimizationObjectivePtr &obj) const override
The sum of the costs for the sequence of segments that make up the path, computed using OptimizationO...
Definition PathGeometric.cpp:101
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
This namespace contains code that is specific to planning under geometric constraints.
Definition GeneticSearch.h:48
A class to store the exit status of Planner::solve().
Definition PlannerStatus.h:49