Public Member Functions | Protected Member Functions | Protected Attributes
ompl_interface::ModelBasedPlanningContext Class Reference

#include <model_based_planning_context.h>

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

List of all members.

Public Member Functions

bool benchmark (double timeout, unsigned int count, const std::string &filename="")
virtual void clear ()
virtual void configure ()
void convertPath (const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
const robot_state::RobotStategetCompleteInitialRobotState () const
const
constraint_samplers::ConstraintSamplerManagerPtr
getConstraintSamplerManager ()
const
robot_model::JointModelGroup
getJointModelGroup () 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
const ot::Benchmark & getOMPLBenchmark () const
ot::Benchmark & getOMPLBenchmark ()
const og::SimpleSetup & getOMPLSimpleSetup () const
og::SimpleSetup & getOMPLSimpleSetup ()
const ModelBasedStateSpacePtrgetOMPLStateSpace () const
const
kinematic_constraints::KinematicConstraintSetPtr
getPathConstraints () const
const
robot_model::RobotModelConstPtr
getRobotModel () const
bool getSolutionPath (robot_trajectory::RobotTrajectory &traj) const
const
ModelBasedPlanningContextSpecification
getSpecification () const
const std::map< std::string,
std::string > & 
getSpecificationConfig () const
void interpolateSolution ()
 ModelBasedPlanningContext (const std::string &name, const ModelBasedPlanningContextSpecification &spec)
void setCompleteInitialState (const robot_state::RobotState &complete_initial_robot_state)
void setConstraintSamplerManager (const constraint_samplers::ConstraintSamplerManagerPtr &csm)
void setConstraintsApproximations (const ConstraintsLibraryConstPtr &constraints_library)
bool setGoalConstraints (const std::vector< moveit_msgs::Constraints > &goal_constraints, const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
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.
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)
virtual bool solve (planning_interface::MotionPlanResponse &res)
virtual bool solve (planning_interface::MotionPlanDetailedResponse &res)
bool solve (double timeout, unsigned int count)
virtual bool terminate ()
bool useStateValidityCache () const
void useStateValidityCache (bool flag)
virtual ~ModelBasedPlanningContext ()

Protected Member Functions

virtual ob::StateSamplerPtr allocPathConstrainedSampler (const ompl::base::StateSpace *ss) const
virtual ob::GoalPtr constructGoal ()
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator (const std::string &peval) const
void postSolve ()
void preSolve ()
void registerTerminationCondition (const ob::PlannerTerminationCondition &ptc)
void unregisterTerminationCondition ()
virtual void useConfig ()

Protected Attributes

robot_state::RobotState complete_initial_robot_state_
std::vector
< kinematic_constraints::KinematicConstraintSetPtr
goal_constraints_
double last_plan_time_
 the time spent computing the last plan
double last_simplify_time_
 the time spent simplifying the last plan
unsigned int max_goal_samples_
 maximum number of valid states to store in the goal region for any planning request (when such sampling is possible)
unsigned int max_goal_sampling_attempts_
 maximum number of attempts to be made at sampling a goal states
unsigned int max_planning_threads_
 when planning in parallel, this is the maximum number of threads to use at one time
double max_solution_segment_length_
 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
unsigned int max_state_sampling_attempts_
 maximum number of attempts to be made at sampling a state when attempting to find valid states that satisfy some set of constraints
unsigned int minimum_waypoint_count_
 the minimum number of points to include on the solution path (interpolation is used to reach this number, if needed)
ot::Benchmark ompl_benchmark_
 the OMPL tool for benchmarking planners
ot::ParallelPlan ompl_parallel_plan_
 tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_simple_setup_
og::SimpleSetup ompl_simple_setup_
 the OMPL planning context; this contains the problem definition and the planner used
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
moveit_msgs::Constraints path_constraints_msg_
const
ob::PlannerTerminationCondition * 
ptc_
boost::mutex ptc_lock_
bool simplify_solutions_
std::vector< int > space_signature_
ModelBasedPlanningContextSpecification spec_
bool use_state_validity_cache_

Detailed Description

Definition at line 77 of file model_based_planning_context.h.


Constructor & Destructor Documentation

Definition at line 54 of file model_based_planning_context.cpp.

Definition at line 83 of file model_based_planning_context.h.


Member Function Documentation

ompl::base::StateSamplerPtr ompl_interface::ModelBasedPlanningContext::allocPathConstrainedSampler ( const ompl::base::StateSpace *  ss) const [protected, virtual]

Definition at line 130 of file model_based_planning_context.cpp.

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

Definition at line 378 of file model_based_planning_context.cpp.

Definition at line 174 of file model_based_planning_context.cpp.

ompl::base::GoalPtr ompl_interface::ModelBasedPlanningContext::constructGoal ( ) [protected, virtual]

Definition at line 294 of file model_based_planning_context.cpp.

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

Definition at line 269 of file model_based_planning_context.cpp.

Definition at line 118 of file model_based_planning_context.h.

Definition at line 224 of file model_based_planning_context.h.

Definition at line 113 of file model_based_planning_context.h.

Definition at line 287 of file model_based_planning_context.h.

Definition at line 293 of file model_based_planning_context.h.

Definition at line 178 of file model_based_planning_context.h.

Definition at line 166 of file model_based_planning_context.h.

Definition at line 190 of file model_based_planning_context.h.

Definition at line 202 of file model_based_planning_context.h.

Definition at line 154 of file model_based_planning_context.h.

Definition at line 213 of file model_based_planning_context.h.

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

Definition at line 138 of file model_based_planning_context.h.

Definition at line 143 of file model_based_planning_context.h.

const og::SimpleSetup& ompl_interface::ModelBasedPlanningContext::getOMPLSimpleSetup ( ) const [inline]

Definition at line 128 of file model_based_planning_context.h.

Definition at line 133 of file model_based_planning_context.h.

Definition at line 123 of file model_based_planning_context.h.

Definition at line 148 of file model_based_planning_context.h.

ompl::base::ProjectionEvaluatorPtr ompl_interface::ModelBasedPlanningContext::getProjectionEvaluator ( const std::string &  peval) const [protected, virtual]

Definition at line 88 of file model_based_planning_context.cpp.

Definition at line 108 of file model_based_planning_context.h.

Definition at line 279 of file model_based_planning_context.cpp.

Definition at line 93 of file model_based_planning_context.h.

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

Definition at line 98 of file model_based_planning_context.h.

Definition at line 260 of file model_based_planning_context.cpp.

Definition at line 410 of file model_based_planning_context.cpp.

Definition at line 395 of file model_based_planning_context.cpp.

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

Definition at line 577 of file model_based_planning_context.cpp.

Definition at line 319 of file model_based_planning_context.cpp.

Definition at line 229 of file model_based_planning_context.h.

Definition at line 248 of file model_based_planning_context.h.

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 346 of file model_based_planning_context.cpp.

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

Definition at line 184 of file model_based_planning_context.h.

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

Definition at line 172 of file model_based_planning_context.h.

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

Definition at line 196 of file model_based_planning_context.h.

Definition at line 208 of file model_based_planning_context.h.

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

Definition at line 160 of file model_based_planning_context.h.

Get the minimum number of waypoints along the solution path.

Definition at line 219 of file model_based_planning_context.h.

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

Definition at line 335 of file model_based_planning_context.cpp.

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

Definition at line 239 of file model_based_planning_context.cpp.

Definition at line 76 of file model_based_planning_context.cpp.

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

Definition at line 103 of file model_based_planning_context.h.

Definition at line 288 of file model_based_planning_context.cpp.

Definition at line 254 of file model_based_planning_context.cpp.

Definition at line 263 of file model_based_planning_context.h.

Definition at line 268 of file model_based_planning_context.h.

bool ompl_interface::ModelBasedPlanningContext::solve ( double  timeout,
unsigned int  count 
)

Definition at line 500 of file model_based_planning_context.cpp.

Definition at line 583 of file model_based_planning_context.cpp.

Definition at line 197 of file model_based_planning_context.cpp.

Definition at line 253 of file model_based_planning_context.h.

Definition at line 258 of file model_based_planning_context.h.


Member Data Documentation

Definition at line 327 of file model_based_planning_context.h.

Definition at line 342 of file model_based_planning_context.h.

the time spent computing the last plan

Definition at line 348 of file model_based_planning_context.h.

the time spent simplifying the last plan

Definition at line 351 of file model_based_planning_context.h.

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

Definition at line 354 of file model_based_planning_context.h.

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

Definition at line 360 of file model_based_planning_context.h.

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

Definition at line 363 of file model_based_planning_context.h.

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 366 of file model_based_planning_context.h.

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 357 of file model_based_planning_context.h.

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

Definition at line 369 of file model_based_planning_context.h.

the OMPL tool for benchmarking planners

Definition at line 333 of file model_based_planning_context.h.

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

Definition at line 336 of file model_based_planning_context.h.

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

Definition at line 330 of file model_based_planning_context.h.

Definition at line 340 of file model_based_planning_context.h.

Definition at line 341 of file model_based_planning_context.h.

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

Definition at line 344 of file model_based_planning_context.h.

Definition at line 345 of file model_based_planning_context.h.

Definition at line 373 of file model_based_planning_context.h.

Definition at line 338 of file model_based_planning_context.h.

Definition at line 325 of file model_based_planning_context.h.

Definition at line 371 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 Mon Oct 6 2014 11:12:04