moveit2
The MoveIt Motion Planning Framework for ROS 2.
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]
Collaboration diagram for ompl_interface::ModelBasedPlanningContext:
Collaboration graph
[legend]

Public Member Functions

 ModelBasedPlanningContext (const std::string &name, const ModelBasedPlanningContextSpecification &spec)
 
 ~ModelBasedPlanningContext () override
 
void solve (planning_interface::MotionPlanResponse &res) override
 Solve the motion planning problem and store the result in res. This function should not clear data structures before computing. The constructor and clear() do that. More...
 
void solve (planning_interface::MotionPlanDetailedResponse &res) override
 Solve the motion planning problem and store the detailed result in res. This function should not clear data structures before computing. The constructor and clear() do that. More...
 
void clear () override
 Clear the data structures used by the planner. More...
 
bool terminate () override
 If solve() is running, terminate the computation. Return false if termination not possible. No-op if solve() is not running (returns true). More...
 
const ModelBasedPlanningContextSpecificationgetSpecification () const
 
const std::map< std::string, std::string > & getSpecificationConfig () const
 
void setSpecificationConfig (const std::map< std::string, std::string > &config)
 
const moveit::core::RobotModelConstPtr & getRobotModel () const
 
const moveit::core::JointModelGroupgetJointModelGroup () const
 
const moveit::core::RobotStategetCompleteInitialRobotState () const
 
const ModelBasedStateSpacePtr & getOMPLStateSpace () const
 
const og::SimpleSetupPtr & getOMPLSimpleSetup () const
 
og::SimpleSetupPtr & getOMPLSimpleSetup ()
 
const ot::Benchmark & getOMPLBenchmark () const
 
ot::Benchmark & getOMPLBenchmark ()
 
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints () const
 
unsigned int getMaximumStateSamplingAttempts () const
 
void setMaximumStateSamplingAttempts (unsigned int max_state_sampling_attempts)
 
unsigned int getMaximumGoalSamplingAttempts () const
 
void setMaximumGoalSamplingAttempts (unsigned int max_goal_sampling_attempts)
 
unsigned int getMaximumGoalSamples () const
 
void setMaximumGoalSamples (unsigned int max_goal_samples)
 
unsigned int getMaximumPlanningThreads () const
 
void setMaximumPlanningThreads (unsigned int max_planning_threads)
 
double getMaximumSolutionSegmentLength () const
 
void setMaximumSolutionSegmentLength (double mssl)
 
unsigned int getMinimumWaypointCount () const
 
void setMinimumWaypointCount (unsigned int mwc)
 Get the minimum number of waypoints along the solution path. More...
 
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager ()
 
void setConstraintSamplerManager (const constraint_samplers::ConstraintSamplerManagerPtr &csm)
 
void setVerboseStateValidityChecks (bool flag)
 
void setProjectionEvaluator (const std::string &peval)
 
void setPlanningVolume (const moveit_msgs::msg::WorkspaceParameters &wparams)
 
void setCompleteInitialState (const moveit::core::RobotState &complete_initial_robot_state)
 
bool setGoalConstraints (const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
 
bool setPathConstraints (const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
 
void setConstraintsApproximations (const ConstraintsLibraryPtr &constraints_library)
 
ConstraintsLibraryPtr getConstraintsLibraryNonConst ()
 
const ConstraintsLibraryPtr & getConstraintsLibrary () const
 
bool simplifySolutions () const
 
void simplifySolutions (bool flag)
 
void setInterpolation (bool flag)
 
void setHybridize (bool flag)
 
const moveit_msgs::msg::MoveItErrorCodes solve (double timeout, unsigned int count)
 
bool benchmark (double timeout, unsigned int count, const std::string &filename="")
 
double getLastPlanTime () const
 
double getLastSimplifyTime () const
 
void simplifySolution (double timeout)
 
void interpolateSolution ()
 
bool getSolutionPath (robot_trajectory::RobotTrajectory &traj) const
 
void convertPath (const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
 
bool loadConstraintApproximations (const rclcpp::Node::SharedPtr &node)
 Look up param server 'constraint_approximations' and use its value as the path to load constraint approximations to. More...
 
bool saveConstraintApproximations (const rclcpp::Node::SharedPtr &node)
 Look up param server 'constraint_approximations' and use its value as the path to save constraint approximations to. More...
 
virtual void configure (const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations)
 Configure ompl_simple_setup_ and optionally the constraints_library_. More...
 
- Public Member Functions inherited from planning_interface::PlanningContext
 PlanningContext (const std::string &name, const std::string &group)
 Construct a planning context named name for the group group. More...
 
virtual ~PlanningContext ()
 
const std::string & getGroupName () const
 Get the name of the group this planning context is for. More...
 
const std::string & getName () const
 Get the name of this planning context. More...
 
const planning_scene::PlanningSceneConstPtr & getPlanningScene () const
 Get the planning scene associated to this planning context. More...
 
const MotionPlanRequestgetMotionPlanRequest () const
 Get the motion plan request associated to this planning context. More...
 
void setPlanningScene (const planning_scene::PlanningSceneConstPtr &planning_scene)
 Set the planning scene for this context. More...
 
void setMotionPlanRequest (const MotionPlanRequest &request)
 Set the planning request for this context. More...
 

Protected Member Functions

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

Protected Attributes

ModelBasedPlanningContextSpecification spec_
 
moveit::core::RobotState complete_initial_robot_state_
 
og::SimpleSetupPtr ompl_simple_setup_
 the OMPL planning context; this contains the problem definition and the planner used 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...
 
std::vector< int > space_signature_
 
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
 
moveit_msgs::msg::Constraints path_constraints_msg_
 
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
 
const ob::PlannerTerminationCondition * ptc_
 
std::mutex ptc_lock_
 
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_state_sampling_attempts_
 
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 minimum_waypoint_count_
 
bool multi_query_planning_enabled_
 when false, clears planners before running solve() More...
 
ConstraintsLibraryPtr constraints_library_
 
bool simplify_solutions_
 
bool interpolate_
 
bool hybridize_
 
- Protected Attributes inherited from planning_interface::PlanningContext
std::string name_
 The name of this planning context. More...
 
std::string group_
 The group (as in the SRDF) this planning context is for. More...
 
planning_scene::PlanningSceneConstPtr planning_scene_
 The planning scene for this context. More...
 
MotionPlanRequest request_
 The planning request for this context. More...
 

Detailed Description

Definition at line 87 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 81 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ ~ModelBasedPlanningContext()

ompl_interface::ModelBasedPlanningContext::~ModelBasedPlanningContext ( )
inlineoverride

Definition at line 92 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 235 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ benchmark()

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

Definition at line 697 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ clear()

void ompl_interface::ModelBasedPlanningContext::clear ( )
overridevirtual

Clear the data structures used by the planner.

Implements planning_interface::PlanningContext.

Definition at line 627 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ configure()

void ompl_interface::ModelBasedPlanningContext::configure ( const rclcpp::Node::SharedPtr &  node,
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
nodeROS node used to load the constraint approximations.
use_constraints_approximationsSet to true if we want to load the constraint approximation.

Definition at line 109 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ constructGoal()

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

Definition at line 519 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ constructPlannerTerminationCondition()

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

Definition at line 553 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ convertPath()

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

Definition at line 490 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCompleteInitialRobotState()

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

Definition at line 127 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getConstraintSamplerManager()

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

Definition at line 233 of file model_based_planning_context.h.

◆ getConstraintsLibrary()

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

Definition at line 267 of file model_based_planning_context.h.

◆ getConstraintsLibraryNonConst()

ConstraintsLibraryPtr ompl_interface::ModelBasedPlanningContext::getConstraintsLibraryNonConst ( )
inline

Definition at line 262 of file model_based_planning_context.h.

◆ getJointModelGroup()

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

Definition at line 122 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getLastPlanTime()

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

Definition at line 307 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getLastSimplifyTime()

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

Definition at line 313 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getMaximumGoalSamples()

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

Definition at line 187 of file model_based_planning_context.h.

◆ getMaximumGoalSamplingAttempts()

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

Definition at line 175 of file model_based_planning_context.h.

◆ getMaximumPlanningThreads()

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

Definition at line 199 of file model_based_planning_context.h.

◆ getMaximumSolutionSegmentLength()

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

Definition at line 211 of file model_based_planning_context.h.

◆ getMaximumStateSamplingAttempts()

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

Definition at line 163 of file model_based_planning_context.h.

◆ getMinimumWaypointCount()

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

Definition at line 222 of file model_based_planning_context.h.

◆ getOMPLBenchmark() [1/2]

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

Definition at line 152 of file model_based_planning_context.h.

◆ getOMPLBenchmark() [2/2]

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

Definition at line 147 of file model_based_planning_context.h.

◆ getOMPLSimpleSetup() [1/2]

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

Definition at line 142 of file model_based_planning_context.h.

◆ getOMPLSimpleSetup() [2/2]

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

Definition at line 137 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getOMPLStateSpace()

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

Definition at line 132 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getPathConstraints()

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

Definition at line 157 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getProjectionEvaluator()

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

Definition at line 166 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getRobotModel()

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

Definition at line 117 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ getSolutionPath()

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

Definition at line 501 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getSpecification()

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

Definition at line 102 of file model_based_planning_context.h.

◆ getSpecificationConfig()

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

Definition at line 107 of file model_based_planning_context.h.

◆ interpolateSolution()

void ompl_interface::ModelBasedPlanningContext::interpolateSolution ( )

Definition at line 462 of file model_based_planning_context.cpp.

Here is the caller graph for this function:

◆ loadConstraintApproximations()

bool ompl_interface::ModelBasedPlanningContext::loadConstraintApproximations ( const rclcpp::Node::SharedPtr &  node)

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

Definition at line 1056 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ logPlannerStatus()

int32_t ompl_interface::ModelBasedPlanningContext::logPlannerStatus ( const og::SimpleSetupPtr &  ompl_simple_setup)
protected

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

Definition at line 974 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ postSolve()

void ompl_interface::ModelBasedPlanningContext::postSolve ( )
protected

Definition at line 755 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ preSolve()

void ompl_interface::ModelBasedPlanningContext::preSolve ( )
protected

Definition at line 742 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ registerTerminationCondition()

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

Definition at line 962 of file model_based_planning_context.cpp.

Here is the caller graph for this function:

◆ saveConstraintApproximations()

bool ompl_interface::ModelBasedPlanningContext::saveConstraintApproximations ( const rclcpp::Node::SharedPtr &  node)

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

Definition at line 1044 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ setCompleteInitialState()

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

Definition at line 621 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setConstraintSamplerManager()

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

Definition at line 238 of file model_based_planning_context.h.

◆ setConstraintsApproximations()

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

Definition at line 257 of file model_based_planning_context.h.

Here is the caller graph for this function:

◆ setGoalConstraints()

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

Definition at line 664 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ setHybridize()

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

Definition at line 287 of file model_based_planning_context.h.

◆ setInterpolation()

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

Definition at line 282 of file model_based_planning_context.h.

◆ setMaximumGoalSamples()

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

Definition at line 193 of file model_based_planning_context.h.

◆ setMaximumGoalSamplingAttempts()

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

Definition at line 181 of file model_based_planning_context.h.

◆ setMaximumPlanningThreads()

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

Definition at line 205 of file model_based_planning_context.h.

◆ setMaximumSolutionSegmentLength()

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

Definition at line 217 of file model_based_planning_context.h.

◆ setMaximumStateSamplingAttempts()

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

Definition at line 169 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 228 of file model_based_planning_context.h.

◆ setPathConstraints()

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

Definition at line 653 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ setPlanningVolume()

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

Definition at line 433 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ setProjectionEvaluator()

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

Definition at line 154 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ setSpecificationConfig()

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

Definition at line 112 of file model_based_planning_context.h.

◆ setVerboseStateValidityChecks()

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

Definition at line 511 of file model_based_planning_context.cpp.

◆ simplifySolution()

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

Definition at line 452 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ simplifySolutions() [1/2]

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

Definition at line 272 of file model_based_planning_context.h.

◆ simplifySolutions() [2/2]

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

Definition at line 277 of file model_based_planning_context.h.

◆ solve() [1/3]

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

Definition at line 849 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ solve() [2/3]

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

Solve the motion planning problem and store the detailed result in res. This function should not clear data structures before computing. The constructor and clear() do that.

Implements planning_interface::PlanningContext.

Definition at line 801 of file model_based_planning_context.cpp.

Here is the call graph for this function:

◆ solve() [3/3]

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

Solve the motion planning problem and store the result in res. This function should not clear data structures before computing. The constructor and clear() do that.

Implements planning_interface::PlanningContext.

Definition at line 772 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ startSampling()

void ompl_interface::ModelBasedPlanningContext::startSampling ( )
protected

Definition at line 714 of file model_based_planning_context.cpp.

Here is the caller graph for this function:

◆ stopSampling()

void ompl_interface::ModelBasedPlanningContext::stopSampling ( )
protected

Definition at line 728 of file model_based_planning_context.cpp.

Here is the caller graph for this function:

◆ terminate()

bool ompl_interface::ModelBasedPlanningContext::terminate ( )
overridevirtual

If solve() is running, terminate the computation. Return false if termination not possible. No-op if solve() is not running (returns true).

Implements planning_interface::PlanningContext.

Definition at line 1034 of file model_based_planning_context.cpp.

◆ unregisterTerminationCondition()

void ompl_interface::ModelBasedPlanningContext::unregisterTerminationCondition ( )
protected

Definition at line 968 of file model_based_planning_context.cpp.

Here is the caller graph for this function:

◆ useConfig()

void ompl_interface::ModelBasedPlanningContext::useConfig ( )
protectedvirtual

Definition at line 286 of file model_based_planning_context.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ complete_initial_robot_state_

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

Definition at line 395 of file model_based_planning_context.h.

◆ constraints_library_

ConstraintsLibraryPtr ompl_interface::ModelBasedPlanningContext::constraints_library_
protected

Definition at line 446 of file model_based_planning_context.h.

◆ goal_constraints_

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

Definition at line 410 of file model_based_planning_context.h.

◆ hybridize_

bool ompl_interface::ModelBasedPlanningContext::hybridize_
protected

Definition at line 454 of file model_based_planning_context.h.

◆ interpolate_

bool ompl_interface::ModelBasedPlanningContext::interpolate_
protected

Definition at line 451 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 416 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 419 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 423 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 430 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 433 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 437 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 427 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 441 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 444 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 401 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 404 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 398 of file model_based_planning_context.h.

◆ path_constraints_

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

Definition at line 408 of file model_based_planning_context.h.

◆ path_constraints_msg_

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

Definition at line 409 of file model_based_planning_context.h.

◆ ptc_

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

Definition at line 412 of file model_based_planning_context.h.

◆ ptc_lock_

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

Definition at line 413 of file model_based_planning_context.h.

◆ simplify_solutions_

bool ompl_interface::ModelBasedPlanningContext::simplify_solutions_
protected

Definition at line 448 of file model_based_planning_context.h.

◆ space_signature_

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

Definition at line 406 of file model_based_planning_context.h.

◆ spec_

ModelBasedPlanningContextSpecification ompl_interface::ModelBasedPlanningContext::spec_
protected

Definition at line 393 of file model_based_planning_context.h.


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