44 #include <ompl/geometric/SimpleSetup.h>
45 #include <ompl/tools/benchmark/Benchmark.h>
46 #include <ompl/tools/multiplan/ParallelPlan.h>
47 #include <ompl/base/StateStorage.h>
48 #include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
52 namespace ob = ompl::base;
53 namespace og = ompl::geometric;
54 namespace ot = ompl::tools;
60 typedef std::function<ob::PlannerPtr(
const ompl::base::SpaceInformationPtr& si,
const std::string&
name,
67 std::map<std::string, std::string>
config_;
100 void clear()
override;
252 bool setGoalConstraints(
const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
254 moveit_msgs::msg::MoveItErrorCodes* error);
256 moveit_msgs::msg::MoveItErrorCodes* error);
297 const moveit_msgs::msg::MoveItErrorCodes
solve(
double timeout,
unsigned int count);
305 bool benchmark(
double timeout,
unsigned int count,
const std::string& filename =
"");
346 virtual void configure(
const rclcpp::Node::SharedPtr& node,
bool use_constraints_approximations);
386 const ompl::time::point& start);
413 const ob::PlannerTerminationCondition*
ptc_;
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const moveit::core::RobotModelConstPtr & getRobotModel() const
og::SimpleSetupPtr & getOMPLSimpleSetup()
void setHybridize(bool flag)
int32_t logPlannerStatus(const og::SimpleSetupPtr &ompl_simple_setup)
Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode.
void setVerboseStateValidityChecks(bool flag)
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const
unsigned int minimum_waypoint_count_
void clear() override
Clear the data structures used by the planner.
bool getSolutionPath(robot_trajectory::RobotTrajectory &traj) const
double last_plan_time_
the time spent computing the last plan
void registerTerminationCondition(const ob::PlannerTerminationCondition &ptc)
const ob::PlannerTerminationCondition * ptc_
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
void setMaximumSolutionSegmentLength(double mssl)
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
bool loadConstraintApproximations(const rclcpp::Node::SharedPtr &node)
Look up param server 'constraint_approximations' and use its value as the path to load constraint app...
std::vector< int > space_signature_
void setMaximumPlanningThreads(unsigned int max_planning_threads)
const moveit::core::RobotState & getCompleteInitialRobotState() const
bool setPathConstraints(const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
const moveit::core::JointModelGroup * getJointModelGroup() const
ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec)
const ConstraintsLibraryPtr & getConstraintsLibrary() const
void interpolateSolution()
virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout, const ompl::time::point &start)
void setInterpolation(bool flag)
bool saveConstraintApproximations(const rclcpp::Node::SharedPtr &node)
Look up param server 'constraint_approximations' and use its value as the path to save constraint app...
const ModelBasedPlanningContextSpecification & getSpecification() const
double getLastPlanTime() const
bool multi_query_planning_enabled_
when false, clears planners before running solve()
virtual void configure(const rclcpp::Node::SharedPtr &node, bool use_constraints_approximations)
Configure ompl_simple_setup_ and optionally the constraints_library_.
void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
const ot::Benchmark & getOMPLBenchmark() const
bool setGoalConstraints(const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
unsigned int getMaximumGoalSamplingAttempts() const
~ModelBasedPlanningContext() override
const std::map< std::string, std::string > & getSpecificationConfig() const
unsigned int max_goal_sampling_attempts_
maximum number of attempts to be made at sampling a goal states
void setCompleteInitialState(const moveit::core::RobotState &complete_initial_robot_state)
unsigned int getMaximumGoalSamples() const
void simplifySolutions(bool flag)
unsigned int getMinimumWaypointCount() const
og::SimpleSetupPtr ompl_simple_setup_
the OMPL planning context; this contains the problem definition and the planner used
moveit::core::RobotState complete_initial_robot_state_
unsigned int max_goal_samples_
ConstraintsLibraryPtr getConstraintsLibraryNonConst()
void setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters &wparams)
void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr &csm)
double getLastSimplifyTime() const
moveit_msgs::msg::Constraints path_constraints_msg_
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
ConstraintsLibraryPtr constraints_library_
void unregisterTerminationCondition()
unsigned int getMaximumStateSamplingAttempts() const
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
bool benchmark(double timeout, unsigned int count, const std::string &filename="")
bool terminate() override
If solve() is running, terminate the computation. Return false if termination not possible....
virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace *ss) const
ot::Benchmark & getOMPLBenchmark()
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
unsigned int max_state_sampling_attempts_
void simplifySolution(double timeout)
void setProjectionEvaluator(const std::string &peval)
void setMaximumGoalSamples(unsigned int max_goal_samples)
bool simplifySolutions() const
ModelBasedPlanningContextSpecification spec_
void setSpecificationConfig(const std::map< std::string, std::string > &config)
double getMaximumSolutionSegmentLength() const
unsigned int getMaximumPlanningThreads() const
ot::ParallelPlan ompl_parallel_plan_
tool used to compute multiple plans in parallel; this uses the problem definition maintained by ompl_...
bool solve(planning_interface::MotionPlanResponse &res) override
Solve the motion planning problem and store the result in res. This function should not clear data st...
virtual ob::GoalPtr constructGoal()
double last_simplify_time_
the time spent simplifying the last plan
double max_solution_segment_length_
void setConstraintsApproximations(const ConstraintsLibraryPtr &constraints_library)
Representation of a particular planning context – the planning scene and the request are known,...
Maintain a sequence of waypoints and the time durations between these waypoints.
The MoveIt interface to OMPL.
std::function< ob::PlannerPtr(const ompl::base::SpaceInformationPtr &si, const std::string &name, const ModelBasedPlanningContextSpecification &spec)> ConfiguredPlannerAllocator
MOVEIT_CLASS_FORWARD(ValidStateSampler)
std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
ModelBasedStateSpacePtr state_space_
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ob::ConstrainedStateSpacePtr constrained_state_space_
OMPL constrained state space to handle path constraints.
std::map< std::string, std::string > config_
ConfiguredPlannerSelector planner_selector_
og::SimpleSetupPtr ompl_simple_setup_