Go to the documentation of this file.
43 #include <ompl/geometric/SimpleSetup.h>
44 #include <ompl/tools/benchmark/Benchmark.h>
45 #include <ompl/tools/multiplan/ParallelPlan.h>
46 #include <ompl/base/StateStorage.h>
50 namespace ob = ompl::base;
51 namespace og = ompl::geometric;
52 namespace ot = ompl::tools;
57 struct ModelBasedPlanningContextSpecification;
58 typedef std::function<ob::PlannerPtr(
const ompl::base::SpaceInformationPtr& si,
const std::string& name,
59 const ModelBasedPlanningContextSpecification& spec)>
63 struct ModelBasedPlanningContextSpecification
65 std::map<std::string, std::string>
config_;
85 void clear()
override;
103 const moveit::core::RobotModelConstPtr&
getRobotModel()
const
237 bool setGoalConstraints(
const std::vector<moveit_msgs::Constraints>& goal_constraints,
238 const moveit_msgs::Constraints& path_constraints, moveit_msgs::MoveItErrorCodes* error);
239 bool setPathConstraints(
const moveit_msgs::Constraints& path_constraints, moveit_msgs::MoveItErrorCodes* error);
280 const moveit_msgs::MoveItErrorCodes
solve(
double timeout,
unsigned int count);
288 bool benchmark(
double timeout,
unsigned int count,
const std::string& filename =
"");
369 const ompl::time::point& start);
375 int32_t
errorCode(
const ompl::base::PlannerStatus& status);
396 const ob::PlannerTerminationCondition*
ptc_;
bool terminate() override
double max_solution_segment_length_
const moveit::core::JointModelGroup * getJointModelGroup() const
void setHybridize(bool flag)
bool loadConstraintApproximations(const ros::NodeHandle &nh)
Look up param server 'constraint_approximations' and use its value as the path to load constraint app...
og::SimpleSetupPtr ompl_simple_setup_
the OMPL planning context; this contains the problem definition and the planner used
void setConstraintsApproximations(const ConstraintsLibraryPtr &constraints_library)
void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr &csm)
unsigned int minimum_waypoint_count_
double getMaximumSolutionSegmentLength() const
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
double getLastPlanTime() const
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const
void setPlanningVolume(const moveit_msgs::WorkspaceParameters &wparams)
std::vector< int > space_signature_
The MoveIt interface to OMPL.
unsigned int max_goal_samples_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
bool simplifySolutions() const
const std::map< std::string, std::string > & getSpecificationConfig() const
ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec)
void setSpecificationConfig(const std::map< std::string, std::string > &config)
unsigned int getMaximumGoalSamples() const
void setCompleteInitialState(const moveit::core::RobotState &complete_initial_robot_state)
void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
void setMaximumSolutionSegmentLength(double mssl)
og::SimpleSetupPtr ompl_simple_setup_
std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
~ModelBasedPlanningContext() override
moveit_msgs::Constraints path_constraints_msg_
virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout, const ompl::time::point &start)
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
void simplifySolution(double timeout)
ConfiguredPlannerSelector planner_selector_
const ModelBasedPlanningContextSpecification & getSpecification() const
const ot::Benchmark & getOMPLBenchmark() const
void setMaximumPlanningThreads(unsigned int max_planning_threads)
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
bool setGoalConstraints(const std::vector< moveit_msgs::Constraints > &goal_constraints, const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
ConstraintsLibraryPtr getConstraintsLibraryNonConst()
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
bool multi_query_planning_enabled_
when false, clears planners before running solve()
bool getSolutionPath(robot_trajectory::RobotTrajectory &traj) const
const ob::PlannerTerminationCondition * ptc_
ModelBasedPlanningContextSpecification spec_
bool setPathConstraints(const moveit_msgs::Constraints &path_constraints, moveit_msgs::MoveItErrorCodes *error)
void interpolateSolution()
bool benchmark(double timeout, unsigned int count, const std::string &filename="")
const ConstraintsLibraryPtr & getConstraintsLibrary() const
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
unsigned int getMaximumPlanningThreads() const
void unregisterTerminationCondition()
unsigned int max_state_sampling_attempts_
double last_plan_time_
the time spent computing the last plan
const moveit::core::RobotModelConstPtr & getRobotModel() const
unsigned int getMinimumWaypointCount() const
void setVerboseStateValidityChecks(bool flag)
ot::ParallelPlan ompl_parallel_plan_
tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_...
void setInterpolation(bool flag)
std::map< std::string, std::string > config_
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling a goal states
virtual void configure(const ros::NodeHandle &nh, bool use_constraints_approximations)
Configure ompl_simple_setup_ and optionally the constraints_library_.
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
MOVEIT_CLASS_FORWARD(ConstraintApproximation)
void registerTerminationCondition(const ob::PlannerTerminationCondition &ptc)
unsigned int getMaximumGoalSamplingAttempts() const
ConstraintsLibraryPtr constraints_library_
std::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
bool saveConstraintApproximations(const ros::NodeHandle &nh)
Look up param server 'constraint_approximations' and use its value as the path to save constraint app...
double last_simplify_time_
the time spent simplifying the last plan
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
int32_t errorCode(const ompl::base::PlannerStatus &status)
Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode.
void setMaximumGoalSamples(unsigned int max_goal_samples)
unsigned int getMaximumStateSamplingAttempts() const
ModelBasedStateSpacePtr state_space_
moveit::core::RobotState complete_initial_robot_state_
virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
virtual ob::GoalPtr constructGoal()
bool solve(planning_interface::MotionPlanResponse &res) override
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
const moveit::core::RobotState & getCompleteInitialRobotState() const
void setProjectionEvaluator(const std::string &peval)
double getLastSimplifyTime() const
ompl
Author(s): Ioan Sucan
autogenerated on Sun Jan 12 2025 03:26:51