Loading...
Searching...
No Matches
PathLengthOptimizationObjective.cpp
41ompl::base::PathLengthOptimizationObjective::PathLengthOptimizationObjective(const SpaceInformationPtr &si)
55ompl::base::Cost ompl::base::PathLengthOptimizationObjective::motionCost(const State *s1, const State *s2) const
72ompl::base::InformedSamplerPtr ompl::base::PathLengthOptimizationObjective::allocInformedStateSampler(
Definition of a cost value. Can represent the cost of a motion or the cost of a state.
Definition Cost.h:48
virtual Cost identityCost() const
Get the identity cost value. The identity cost value is the cost c_i such that, for all costs c,...
Definition OptimizationObjective.cpp:106
SpaceInformationPtr si_
The space information for this objective.
Definition OptimizationObjective.h:195
InformedSamplerPtr allocInformedStateSampler(const ProblemDefinitionPtr &probDefn, unsigned int maxNumberCalls) const override
Allocate a state sampler for the path-length objective (i.e., direct ellipsoidal sampling).
Definition PathLengthOptimizationObjective.cpp:72
Cost stateCost(const State *s) const override
Returns identity cost.
Definition PathLengthOptimizationObjective.cpp:50
Cost motionCostHeuristic(const State *s1, const State *s2) const override
the motion cost heuristic for this objective is simply the configuration space distance between s1 an...
Definition PathLengthOptimizationObjective.cpp:60
Cost motionCostBestEstimate(const State *s1, const State *s2) const override
the best motion cost estimate for this objective is simply the configuration space distance between s...
Definition PathLengthOptimizationObjective.cpp:66
Cost motionCost(const State *s1, const State *s2) const override
Motion cost for this objective is defined as the configuration space distance between s1 and s2,...
Definition PathLengthOptimizationObjective.cpp:55
A shared pointer wrapper for ompl::base::ProblemDefinition.
A shared pointer wrapper for ompl::base::SpaceInformation.
This namespace contains sampling based planning routines shared by both planning under geometric cons...
Definition ConstrainedSpaceInformation.h:55
Cost goalRegionCostToGo(const State *state, const Goal *goal)
For use when the cost-to-go of a state under the optimization objective is equivalent to the goal reg...
Definition OptimizationObjective.cpp:195
Main namespace. Contains everything in this library.
Definition MultiLevelPlanarManipulatorDemo.cpp:66