Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ompl_interface::ModelBasedPlanningContext Class Reference

#include <model_based_planning_context.h>

Inheritance diagram for ompl_interface::ModelBasedPlanningContext:
Inheritance graph
[legend]

Public Member Functions

bool benchmark (double timeout, unsigned int count, const std::string &filename="")
 
void clear () override
 
virtual void configure (const ros::NodeHandle &nh, bool use_constraints_approximations)
 Configure ompl_simple_setup_ and optionally the constraints_library_. More...
 
void convertPath (const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
 
const moveit::core::RobotStategetCompleteInitialRobotState () const
 
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager ()
 
const ConstraintsLibraryPtr & getConstraintsLibrary () const
 
ConstraintsLibraryPtr getConstraintsLibraryNonConst ()
 
const moveit::core::JointModelGroupgetJointModelGroup () const
 
double getLastPlanTime () const
 
double getLastSimplifyTime () const
 
unsigned int getMaximumGoalSamples () const
 
unsigned int getMaximumGoalSamplingAttempts () const
 
unsigned int getMaximumPlanningThreads () const
 
double getMaximumSolutionSegmentLength () const
 
unsigned int getMaximumStateSamplingAttempts () const
 
unsigned int getMinimumWaypointCount () const
 
ot::Benchmark & getOMPLBenchmark ()
 
const ot::Benchmark & getOMPLBenchmark () const
 
og::SimpleSetupPtr & getOMPLSimpleSetup ()
 
const og::SimpleSetupPtr & getOMPLSimpleSetup () const
 
const ModelBasedStateSpacePtr & getOMPLStateSpace () const
 
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints () const
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
bool getSolutionPath (robot_trajectory::RobotTrajectory &traj) const
 
const ModelBasedPlanningContextSpecificationgetSpecification () const
 
const std::map< std::string, std::string > & getSpecificationConfig () const
 
void interpolateSolution ()
 
bool loadConstraintApproximations (const ros::NodeHandle &nh)
 Look up param server 'constraint_approximations' and use its value as the path to load constraint approximations to. More...
 
 ModelBasedPlanningContext (const std::string &name, const ModelBasedPlanningContextSpecification &spec)
 
bool saveConstraintApproximations (const ros::NodeHandle &nh)
 Look up param server 'constraint_approximations' and use its value as the path to save constraint approximations to. More...
 
void setCompleteInitialState (const moveit::core::RobotState &complete_initial_robot_state)
 
void setConstraintSamplerManager (const constraint_samplers::ConstraintSamplerManagerPtr &csm)
 
void setConstraintsApproximations (const ConstraintsLibraryPtr &constraints_library)
 
bool setGoalConstraints (const std::vector< moveit_msgs::Constraints > &goal_constraints, const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
 
void setHybridize (bool flag)
 
void setInterpolation (bool flag)
 
void setMaximumGoalSamples (unsigned int max_goal_samples)
 
void setMaximumGoalSamplingAttempts (unsigned int max_goal_sampling_attempts)
 
void setMaximumPlanningThreads (unsigned int max_planning_threads)
 
void setMaximumSolutionSegmentLength (double mssl)
 
void setMaximumStateSamplingAttempts (unsigned int max_state_sampling_attempts)
 
void setMinimumWaypointCount (unsigned int mwc)
 Get the minimum number of waypoints along the solution path. More...
 
bool setPathConstraints (const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
 
void setPlanningVolume (const moveit_msgs::WorkspaceParameters &wparams)
 
void setProjectionEvaluator (const std::string &peval)
 
void setSpecificationConfig (const std::map< std::string, std::string > &config)
 
void setVerboseStateValidityChecks (bool flag)
 
void simplifySolution (double timeout)
 
bool simplifySolutions () const
 
void simplifySolutions (bool flag)
 
const moveit_msgs::MoveItErrorCodes solve (double timeout, unsigned int count)
 
bool solve (planning_interface::MotionPlanDetailedResponse &res) override
 
bool solve (planning_interface::MotionPlanResponse &res) override
 
bool terminate () override
 
 ~ModelBasedPlanningContext () override
 
- Public Member Functions inherited from planning_interface::PlanningContext
const std::string & getGroupName () const
 
const MotionPlanRequestgetMotionPlanRequest () const
 
const std::string & getName () const
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene () const
 
 PlanningContext (const std::string &name, const std::string &group)
 
void setMotionPlanRequest (const MotionPlanRequest &request)
 
void setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene)
 
virtual ~PlanningContext ()
 

Protected Member Functions

virtual ob::StateSamplerPtr allocPathConstrainedSampler (const ompl::base::StateSpace *ss) const
 
virtual ob::GoalPtr constructGoal ()
 
virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition (double timeout, const ompl::time::point &start)
 
int32_t errorCode (const ompl::base::PlannerStatus &status)
 Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode. More...
 
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator (const std::string &peval) const
 
void postSolve ()
 
void preSolve ()
 
void registerTerminationCondition (const ob::PlannerTerminationCondition &ptc)
 
void startSampling ()
 
void stopSampling ()
 
void unregisterTerminationCondition ()
 
virtual void useConfig ()
 

Protected Attributes

moveit::core::RobotState complete_initial_robot_state_
 
ConstraintsLibraryPtr constraints_library_
 
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
 
bool hybridize_
 
bool interpolate_
 
double last_plan_time_
 the time spent computing the last plan More...
 
double last_simplify_time_
 the time spent simplifying the last plan More...
 
unsigned int max_goal_samples_
 
unsigned int max_goal_sampling_attempts_
 maximum number of attempts to be made at sampling a goal states More...
 
unsigned int max_planning_threads_
 when planning in parallel, this is the maximum number of threads to use at one time More...
 
double max_solution_segment_length_
 
unsigned int max_state_sampling_attempts_
 
unsigned int minimum_waypoint_count_
 
bool multi_query_planning_enabled_
 when false, clears planners before running solve() More...
 
ot::Benchmark ompl_benchmark_
 the OMPL tool for benchmarking planners More...
 
ot::ParallelPlan ompl_parallel_plan_
 tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_simple_setup_ More...
 
og::SimpleSetupPtr ompl_simple_setup_
 the OMPL planning context; this contains the problem definition and the planner used More...
 
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
 
moveit_msgs::Constraints path_constraints_msg_
 
const ob::PlannerTerminationCondition * ptc_
 
std::mutex ptc_lock_
 
bool simplify_solutions_
 
std::vector< int > space_signature_
 
ModelBasedPlanningContextSpecification spec_
 
- Protected Attributes inherited from planning_interface::PlanningContext
std::string group_
 
std::string name_
 
planning_scene::PlanningSceneConstPtr planning_scene_
 
MotionPlanRequest request_
 

Detailed Description

Definition at line 105 of file model_based_planning_context.h.

Constructor & Destructor Documentation

◆ ModelBasedPlanningContext()

ompl_interface::ModelBasedPlanningContext::ModelBasedPlanningContext ( const std::string &  name,
const ModelBasedPlanningContextSpecification spec 
)

Definition at line 80 of file model_based_planning_context.cpp.

◆ ~ModelBasedPlanningContext()

ompl_interface::ModelBasedPlanningContext::~ModelBasedPlanningContext ( )
inlineoverride

Definition at line 110 of file model_based_planning_context.h.

Member Function Documentation

◆ allocPathConstrainedSampler()

ompl::base::StateSamplerPtr ompl_interface::ModelBasedPlanningContext::allocPathConstrainedSampler ( const ompl::base::StateSpace *  ss) const
protectedvirtual

Definition at line 207 of file model_based_planning_context.cpp.

◆ benchmark()

bool ompl_interface::ModelBasedPlanningContext::benchmark ( double  timeout,
unsigned int  count,
const std::string &  filename = "" 
)

Definition at line 626 of file model_based_planning_context.cpp.

◆ clear()

void ompl_interface::ModelBasedPlanningContext::clear ( )
overridevirtual

◆ configure()

void ompl_interface::ModelBasedPlanningContext::configure ( const ros::NodeHandle nh,
bool  use_constraints_approximations 
)
virtual

Configure ompl_simple_setup_ and optionally the constraints_library_.

ompl_simple_setup_ gets a start state, state sampler, and state validity checker.

Parameters
nhROS node handle used to load the constraint approximations.
use_constraints_approximationsSet to true if we want to load the constraint approximation.

Definition at line 107 of file model_based_planning_context.cpp.

◆ constructGoal()

ompl::base::GoalPtr ompl_interface::ModelBasedPlanningContext::constructGoal ( )
protectedvirtual

Definition at line 468 of file model_based_planning_context.cpp.

◆ constructPlannerTerminationCondition()

ompl::base::PlannerTerminationCondition ompl_interface::ModelBasedPlanningContext::constructPlannerTerminationCondition ( double  timeout,
const ompl::time::point start 
)
protectedvirtual

Definition at line 495 of file model_based_planning_context.cpp.

◆ convertPath()

void ompl_interface::ModelBasedPlanningContext::convertPath ( const og::PathGeometric &  pg,
robot_trajectory::RobotTrajectory traj 
) const

Definition at line 443 of file model_based_planning_context.cpp.

◆ errorCode()

int32_t ompl_interface::ModelBasedPlanningContext::errorCode ( const ompl::base::PlannerStatus &  status)
protected

Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode.

Definition at line 826 of file model_based_planning_context.cpp.

◆ getCompleteInitialRobotState()

const moveit::core::RobotState& ompl_interface::ModelBasedPlanningContext::getCompleteInitialRobotState ( ) const
inline

Definition at line 145 of file model_based_planning_context.h.

◆ getConstraintSamplerManager()

const constraint_samplers::ConstraintSamplerManagerPtr& ompl_interface::ModelBasedPlanningContext::getConstraintSamplerManager ( )
inline

Definition at line 251 of file model_based_planning_context.h.

◆ getConstraintsLibrary()

const ConstraintsLibraryPtr& ompl_interface::ModelBasedPlanningContext::getConstraintsLibrary ( ) const
inline

Definition at line 283 of file model_based_planning_context.h.

◆ getConstraintsLibraryNonConst()

ConstraintsLibraryPtr ompl_interface::ModelBasedPlanningContext::getConstraintsLibraryNonConst ( )
inline

Definition at line 278 of file model_based_planning_context.h.

◆ getJointModelGroup()

const moveit::core::JointModelGroup* ompl_interface::ModelBasedPlanningContext::getJointModelGroup ( ) const
inline

Definition at line 140 of file model_based_planning_context.h.

◆ getLastPlanTime()

double ompl_interface::ModelBasedPlanningContext::getLastPlanTime ( ) const
inline

Definition at line 323 of file model_based_planning_context.h.

◆ getLastSimplifyTime()

double ompl_interface::ModelBasedPlanningContext::getLastSimplifyTime ( ) const
inline

Definition at line 329 of file model_based_planning_context.h.

◆ getMaximumGoalSamples()

unsigned int ompl_interface::ModelBasedPlanningContext::getMaximumGoalSamples ( ) const
inline

Definition at line 205 of file model_based_planning_context.h.

◆ getMaximumGoalSamplingAttempts()

unsigned int ompl_interface::ModelBasedPlanningContext::getMaximumGoalSamplingAttempts ( ) const
inline

Definition at line 193 of file model_based_planning_context.h.

◆ getMaximumPlanningThreads()

unsigned int ompl_interface::ModelBasedPlanningContext::getMaximumPlanningThreads ( ) const
inline

Definition at line 217 of file model_based_planning_context.h.

◆ getMaximumSolutionSegmentLength()

double ompl_interface::ModelBasedPlanningContext::getMaximumSolutionSegmentLength ( ) const
inline

Definition at line 229 of file model_based_planning_context.h.

◆ getMaximumStateSamplingAttempts()

unsigned int ompl_interface::ModelBasedPlanningContext::getMaximumStateSamplingAttempts ( ) const
inline

Definition at line 181 of file model_based_planning_context.h.

◆ getMinimumWaypointCount()

unsigned int ompl_interface::ModelBasedPlanningContext::getMinimumWaypointCount ( ) const
inline

Definition at line 240 of file model_based_planning_context.h.

◆ getOMPLBenchmark() [1/2]

ot::Benchmark& ompl_interface::ModelBasedPlanningContext::getOMPLBenchmark ( )
inline

Definition at line 170 of file model_based_planning_context.h.

◆ getOMPLBenchmark() [2/2]

const ot::Benchmark& ompl_interface::ModelBasedPlanningContext::getOMPLBenchmark ( ) const
inline

Definition at line 165 of file model_based_planning_context.h.

◆ getOMPLSimpleSetup() [1/2]

og::SimpleSetupPtr& ompl_interface::ModelBasedPlanningContext::getOMPLSimpleSetup ( )
inline

Definition at line 160 of file model_based_planning_context.h.

◆ getOMPLSimpleSetup() [2/2]

const og::SimpleSetupPtr& ompl_interface::ModelBasedPlanningContext::getOMPLSimpleSetup ( ) const
inline

Definition at line 155 of file model_based_planning_context.h.

◆ getOMPLStateSpace()

const ModelBasedStateSpacePtr& ompl_interface::ModelBasedPlanningContext::getOMPLStateSpace ( ) const
inline

Definition at line 150 of file model_based_planning_context.h.

◆ getPathConstraints()

const kinematic_constraints::KinematicConstraintSetPtr& ompl_interface::ModelBasedPlanningContext::getPathConstraints ( ) const
inline

Definition at line 175 of file model_based_planning_context.h.

◆ getProjectionEvaluator()

ompl::base::ProjectionEvaluatorPtr ompl_interface::ModelBasedPlanningContext::getProjectionEvaluator ( const std::string &  peval) const
protectedvirtual

Definition at line 154 of file model_based_planning_context.cpp.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& ompl_interface::ModelBasedPlanningContext::getRobotModel ( ) const
inline

Definition at line 135 of file model_based_planning_context.h.

◆ getSolutionPath()

bool ompl_interface::ModelBasedPlanningContext::getSolutionPath ( robot_trajectory::RobotTrajectory traj) const

Definition at line 454 of file model_based_planning_context.cpp.

◆ getSpecification()

const ModelBasedPlanningContextSpecification& ompl_interface::ModelBasedPlanningContext::getSpecification ( ) const
inline

Definition at line 120 of file model_based_planning_context.h.

◆ getSpecificationConfig()

const std::map<std::string, std::string>& ompl_interface::ModelBasedPlanningContext::getSpecificationConfig ( ) const
inline

Definition at line 125 of file model_based_planning_context.h.

◆ interpolateSolution()

void ompl_interface::ModelBasedPlanningContext::interpolateSolution ( )

Definition at line 415 of file model_based_planning_context.cpp.

◆ loadConstraintApproximations()

bool ompl_interface::ModelBasedPlanningContext::loadConstraintApproximations ( const ros::NodeHandle nh)

Look up param server 'constraint_approximations' and use its value as the path to load constraint approximations to.

Definition at line 894 of file model_based_planning_context.cpp.

◆ postSolve()

void ompl_interface::ModelBasedPlanningContext::postSolve ( )
protected

Definition at line 675 of file model_based_planning_context.cpp.

◆ preSolve()

void ompl_interface::ModelBasedPlanningContext::preSolve ( )
protected

Definition at line 664 of file model_based_planning_context.cpp.

◆ registerTerminationCondition()

void ompl_interface::ModelBasedPlanningContext::registerTerminationCondition ( const ob::PlannerTerminationCondition &  ptc)
protected

Definition at line 814 of file model_based_planning_context.cpp.

◆ saveConstraintApproximations()

bool ompl_interface::ModelBasedPlanningContext::saveConstraintApproximations ( const ros::NodeHandle nh)

Look up param server 'constraint_approximations' and use its value as the path to save constraint approximations to.

Definition at line 882 of file model_based_planning_context.cpp.

◆ setCompleteInitialState()

void ompl_interface::ModelBasedPlanningContext::setCompleteInitialState ( const moveit::core::RobotState complete_initial_robot_state)

Definition at line 554 of file model_based_planning_context.cpp.

◆ setConstraintSamplerManager()

void ompl_interface::ModelBasedPlanningContext::setConstraintSamplerManager ( const constraint_samplers::ConstraintSamplerManagerPtr &  csm)
inline

Definition at line 256 of file model_based_planning_context.h.

◆ setConstraintsApproximations()

void ompl_interface::ModelBasedPlanningContext::setConstraintsApproximations ( const ConstraintsLibraryPtr &  constraints_library)
inline

Definition at line 273 of file model_based_planning_context.h.

◆ setGoalConstraints()

bool ompl_interface::ModelBasedPlanningContext::setGoalConstraints ( const std::vector< moveit_msgs::Constraints > &  goal_constraints,
const moveit_msgs::Constraints &  path_constraints,
moveit_msgs::MoveItErrorCodes *  error 
)

Definition at line 597 of file model_based_planning_context.cpp.

◆ setHybridize()

void ompl_interface::ModelBasedPlanningContext::setHybridize ( bool  flag)
inline

Definition at line 303 of file model_based_planning_context.h.

◆ setInterpolation()

void ompl_interface::ModelBasedPlanningContext::setInterpolation ( bool  flag)
inline

Definition at line 298 of file model_based_planning_context.h.

◆ setMaximumGoalSamples()

void ompl_interface::ModelBasedPlanningContext::setMaximumGoalSamples ( unsigned int  max_goal_samples)
inline

Definition at line 211 of file model_based_planning_context.h.

◆ setMaximumGoalSamplingAttempts()

void ompl_interface::ModelBasedPlanningContext::setMaximumGoalSamplingAttempts ( unsigned int  max_goal_sampling_attempts)
inline

Definition at line 199 of file model_based_planning_context.h.

◆ setMaximumPlanningThreads()

void ompl_interface::ModelBasedPlanningContext::setMaximumPlanningThreads ( unsigned int  max_planning_threads)
inline

Definition at line 223 of file model_based_planning_context.h.

◆ setMaximumSolutionSegmentLength()

void ompl_interface::ModelBasedPlanningContext::setMaximumSolutionSegmentLength ( double  mssl)
inline

Definition at line 235 of file model_based_planning_context.h.

◆ setMaximumStateSamplingAttempts()

void ompl_interface::ModelBasedPlanningContext::setMaximumStateSamplingAttempts ( unsigned int  max_state_sampling_attempts)
inline

Definition at line 187 of file model_based_planning_context.h.

◆ setMinimumWaypointCount()

void ompl_interface::ModelBasedPlanningContext::setMinimumWaypointCount ( unsigned int  mwc)
inline

Get the minimum number of waypoints along the solution path.

Definition at line 246 of file model_based_planning_context.h.

◆ setPathConstraints()

bool ompl_interface::ModelBasedPlanningContext::setPathConstraints ( const moveit_msgs::Constraints &  path_constraints,
moveit_msgs::MoveItErrorCodes *  error 
)

Definition at line 586 of file model_based_planning_context.cpp.

◆ setPlanningVolume()

void ompl_interface::ModelBasedPlanningContext::setPlanningVolume ( const moveit_msgs::WorkspaceParameters &  wparams)

Definition at line 388 of file model_based_planning_context.cpp.

◆ setProjectionEvaluator()

void ompl_interface::ModelBasedPlanningContext::setProjectionEvaluator ( const std::string &  peval)

Definition at line 141 of file model_based_planning_context.cpp.

◆ setSpecificationConfig()

void ompl_interface::ModelBasedPlanningContext::setSpecificationConfig ( const std::map< std::string, std::string > &  config)
inline

Definition at line 130 of file model_based_planning_context.h.

◆ setVerboseStateValidityChecks()

void ompl_interface::ModelBasedPlanningContext::setVerboseStateValidityChecks ( bool  flag)

Definition at line 462 of file model_based_planning_context.cpp.

◆ simplifySolution()

void ompl_interface::ModelBasedPlanningContext::simplifySolution ( double  timeout)

Definition at line 405 of file model_based_planning_context.cpp.

◆ simplifySolutions() [1/2]

bool ompl_interface::ModelBasedPlanningContext::simplifySolutions ( ) const
inline

Definition at line 288 of file model_based_planning_context.h.

◆ simplifySolutions() [2/2]

void ompl_interface::ModelBasedPlanningContext::simplifySolutions ( bool  flag)
inline

Definition at line 293 of file model_based_planning_context.h.

◆ solve() [1/3]

const moveit_msgs::MoveItErrorCodes ompl_interface::ModelBasedPlanningContext::solve ( double  timeout,
unsigned int  count 
)

Definition at line 762 of file model_based_planning_context.cpp.

◆ solve() [2/3]

bool ompl_interface::ModelBasedPlanningContext::solve ( planning_interface::MotionPlanDetailedResponse res)
overridevirtual

◆ solve() [3/3]

bool ompl_interface::ModelBasedPlanningContext::solve ( planning_interface::MotionPlanResponse res)
overridevirtual

◆ startSampling()

void ompl_interface::ModelBasedPlanningContext::startSampling ( )
protected

Definition at line 644 of file model_based_planning_context.cpp.

◆ stopSampling()

void ompl_interface::ModelBasedPlanningContext::stopSampling ( )
protected

Definition at line 654 of file model_based_planning_context.cpp.

◆ terminate()

bool ompl_interface::ModelBasedPlanningContext::terminate ( )
overridevirtual

◆ unregisterTerminationCondition()

void ompl_interface::ModelBasedPlanningContext::unregisterTerminationCondition ( )
protected

Definition at line 820 of file model_based_planning_context.cpp.

◆ useConfig()

void ompl_interface::ModelBasedPlanningContext::useConfig ( )
protectedvirtual

Definition at line 256 of file model_based_planning_context.cpp.

Member Data Documentation

◆ complete_initial_robot_state_

moveit::core::RobotState ompl_interface::ModelBasedPlanningContext::complete_initial_robot_state_
protected

Definition at line 411 of file model_based_planning_context.h.

◆ constraints_library_

ConstraintsLibraryPtr ompl_interface::ModelBasedPlanningContext::constraints_library_
protected

Definition at line 462 of file model_based_planning_context.h.

◆ goal_constraints_

std::vector<kinematic_constraints::KinematicConstraintSetPtr> ompl_interface::ModelBasedPlanningContext::goal_constraints_
protected

Definition at line 426 of file model_based_planning_context.h.

◆ hybridize_

bool ompl_interface::ModelBasedPlanningContext::hybridize_
protected

Definition at line 470 of file model_based_planning_context.h.

◆ interpolate_

bool ompl_interface::ModelBasedPlanningContext::interpolate_
protected

Definition at line 467 of file model_based_planning_context.h.

◆ last_plan_time_

double ompl_interface::ModelBasedPlanningContext::last_plan_time_
protected

the time spent computing the last plan

Definition at line 432 of file model_based_planning_context.h.

◆ last_simplify_time_

double ompl_interface::ModelBasedPlanningContext::last_simplify_time_
protected

the time spent simplifying the last plan

Definition at line 435 of file model_based_planning_context.h.

◆ max_goal_samples_

unsigned int ompl_interface::ModelBasedPlanningContext::max_goal_samples_
protected

maximum number of valid states to store in the goal region for any planning request (when such sampling is possible)

Definition at line 439 of file model_based_planning_context.h.

◆ max_goal_sampling_attempts_

unsigned int ompl_interface::ModelBasedPlanningContext::max_goal_sampling_attempts_
protected

maximum number of attempts to be made at sampling a goal states

Definition at line 446 of file model_based_planning_context.h.

◆ max_planning_threads_

unsigned int ompl_interface::ModelBasedPlanningContext::max_planning_threads_
protected

when planning in parallel, this is the maximum number of threads to use at one time

Definition at line 449 of file model_based_planning_context.h.

◆ max_solution_segment_length_

double ompl_interface::ModelBasedPlanningContext::max_solution_segment_length_
protected

the maximum length that is allowed for segments that make up the motion plan; by default this is 1% from the extent of the space

Definition at line 453 of file model_based_planning_context.h.

◆ max_state_sampling_attempts_

unsigned int ompl_interface::ModelBasedPlanningContext::max_state_sampling_attempts_
protected

maximum number of attempts to be made at sampling a state when attempting to find valid states that satisfy some set of constraints

Definition at line 443 of file model_based_planning_context.h.

◆ minimum_waypoint_count_

unsigned int ompl_interface::ModelBasedPlanningContext::minimum_waypoint_count_
protected

the minimum number of points to include on the solution path (interpolation is used to reach this number, if needed)

Definition at line 457 of file model_based_planning_context.h.

◆ multi_query_planning_enabled_

bool ompl_interface::ModelBasedPlanningContext::multi_query_planning_enabled_
protected

when false, clears planners before running solve()

Definition at line 460 of file model_based_planning_context.h.

◆ ompl_benchmark_

ot::Benchmark ompl_interface::ModelBasedPlanningContext::ompl_benchmark_
protected

the OMPL tool for benchmarking planners

Definition at line 417 of file model_based_planning_context.h.

◆ ompl_parallel_plan_

ot::ParallelPlan ompl_interface::ModelBasedPlanningContext::ompl_parallel_plan_
protected

tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_simple_setup_

Definition at line 420 of file model_based_planning_context.h.

◆ ompl_simple_setup_

og::SimpleSetupPtr ompl_interface::ModelBasedPlanningContext::ompl_simple_setup_
protected

the OMPL planning context; this contains the problem definition and the planner used

Definition at line 414 of file model_based_planning_context.h.

◆ path_constraints_

kinematic_constraints::KinematicConstraintSetPtr ompl_interface::ModelBasedPlanningContext::path_constraints_
protected

Definition at line 424 of file model_based_planning_context.h.

◆ path_constraints_msg_

moveit_msgs::Constraints ompl_interface::ModelBasedPlanningContext::path_constraints_msg_
protected

Definition at line 425 of file model_based_planning_context.h.

◆ ptc_

const ob::PlannerTerminationCondition* ompl_interface::ModelBasedPlanningContext::ptc_
protected

Definition at line 428 of file model_based_planning_context.h.

◆ ptc_lock_

std::mutex ompl_interface::ModelBasedPlanningContext::ptc_lock_
protected

Definition at line 429 of file model_based_planning_context.h.

◆ simplify_solutions_

bool ompl_interface::ModelBasedPlanningContext::simplify_solutions_
protected

Definition at line 464 of file model_based_planning_context.h.

◆ space_signature_

std::vector<int> ompl_interface::ModelBasedPlanningContext::space_signature_
protected

Definition at line 422 of file model_based_planning_context.h.

◆ spec_

ModelBasedPlanningContextSpecification ompl_interface::ModelBasedPlanningContext::spec_
protected

Definition at line 409 of file model_based_planning_context.h.


The documentation for this class was generated from the following files:


ompl
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:24:37