moveit2
The MoveIt Motion Planning Framework for ROS 2.
model_based_planning_context.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
43 
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>
49 
50 namespace ompl_interface
51 {
52 namespace ob = ompl::base;
53 namespace og = ompl::geometric;
54 namespace ot = ompl::tools;
55 
56 MOVEIT_CLASS_FORWARD(ModelBasedPlanningContext); // Defines ModelBasedPlanningContextPtr, ConstPtr, WeakPtr... etc
57 MOVEIT_CLASS_FORWARD(ConstraintsLibrary); // Defines ConstraintsLibraryPtr, ConstPtr, WeakPtr... etc
58 
60 typedef std::function<ob::PlannerPtr(const ompl::base::SpaceInformationPtr& si, const std::string& name,
63 typedef std::function<ConfiguredPlannerAllocator(const std::string& planner_type)> ConfiguredPlannerSelector;
64 
66 {
67  std::map<std::string, std::string> config_;
69  constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
70 
71  ModelBasedStateSpacePtr state_space_;
72  og::SimpleSetupPtr ompl_simple_setup_; // pass in the correct simple setup type
73 
85  ob::ConstrainedStateSpacePtr constrained_state_space_;
86 };
87 
89 {
90 public:
92 
94  {
95  }
96 
99 
100  void clear() override;
101  bool terminate() override;
102 
104  {
105  return spec_;
106  }
107 
108  const std::map<std::string, std::string>& getSpecificationConfig() const
109  {
110  return spec_.config_;
111  }
112 
113  void setSpecificationConfig(const std::map<std::string, std::string>& config)
114  {
115  spec_.config_ = config;
116  }
117 
118  const moveit::core::RobotModelConstPtr& getRobotModel() const
119  {
120  return spec_.state_space_->getRobotModel();
121  }
122 
124  {
125  return spec_.state_space_->getJointModelGroup();
126  }
127 
129  {
131  }
132 
133  const ModelBasedStateSpacePtr& getOMPLStateSpace() const
134  {
135  return spec_.state_space_;
136  }
137 
138  const og::SimpleSetupPtr& getOMPLSimpleSetup() const
139  {
140  return ompl_simple_setup_;
141  }
142 
143  og::SimpleSetupPtr& getOMPLSimpleSetup()
144  {
145  return ompl_simple_setup_;
146  }
147 
148  const ot::Benchmark& getOMPLBenchmark() const
149  {
150  return ompl_benchmark_;
151  }
152 
153  ot::Benchmark& getOMPLBenchmark()
154  {
155  return ompl_benchmark_;
156  }
157 
158  const kinematic_constraints::KinematicConstraintSetPtr& getPathConstraints() const
159  {
160  return path_constraints_;
161  }
162 
163  /* \brief Get the maximum number of sampling attempts allowed when sampling states is needed */
164  unsigned int getMaximumStateSamplingAttempts() const
165  {
167  }
168 
169  /* \brief Set the maximum number of sampling attempts allowed when sampling states is needed */
170  void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
171  {
172  max_state_sampling_attempts_ = max_state_sampling_attempts;
173  }
174 
175  /* \brief Get the maximum number of sampling attempts allowed when sampling goals is needed */
176  unsigned int getMaximumGoalSamplingAttempts() const
177  {
179  }
180 
181  /* \brief Set the maximum number of sampling attempts allowed when sampling goals is needed */
182  void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
183  {
184  max_goal_sampling_attempts_ = max_goal_sampling_attempts;
185  }
186 
187  /* \brief Get the maximum number of valid goal samples to store */
188  unsigned int getMaximumGoalSamples() const
189  {
190  return max_goal_samples_;
191  }
192 
193  /* \brief Set the maximum number of valid goal samples to store */
194  void setMaximumGoalSamples(unsigned int max_goal_samples)
195  {
196  max_goal_samples_ = max_goal_samples;
197  }
198 
199  /* \brief Get the maximum number of planning threads allowed */
200  unsigned int getMaximumPlanningThreads() const
201  {
202  return max_planning_threads_;
203  }
204 
205  /* \brief Set the maximum number of planning threads */
206  void setMaximumPlanningThreads(unsigned int max_planning_threads)
207  {
208  max_planning_threads_ = max_planning_threads;
209  }
210 
211  /* \brief Get the maximum solution segment length */
213  {
215  }
216 
217  /* \brief Set the maximum solution segment length */
219  {
221  }
222 
223  unsigned int getMinimumWaypointCount() const
224  {
226  }
227 
229  void setMinimumWaypointCount(unsigned int mwc)
230  {
232  }
233 
234  const constraint_samplers::ConstraintSamplerManagerPtr& getConstraintSamplerManager()
235  {
237  }
238 
239  void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr& csm)
240  {
242  }
243 
244  void setVerboseStateValidityChecks(bool flag);
245 
246  void setProjectionEvaluator(const std::string& peval);
247 
248  void setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters& wparams);
249 
250  void setCompleteInitialState(const moveit::core::RobotState& complete_initial_robot_state);
251 
252  bool setGoalConstraints(const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
253  const moveit_msgs::msg::Constraints& path_constraints,
254  moveit_msgs::msg::MoveItErrorCodes* error);
255  bool setPathConstraints(const moveit_msgs::msg::Constraints& path_constraints,
256  moveit_msgs::msg::MoveItErrorCodes* error);
257 
258  void setConstraintsApproximations(const ConstraintsLibraryPtr& constraints_library)
259  {
260  constraints_library_ = constraints_library;
261  }
262 
263  ConstraintsLibraryPtr getConstraintsLibraryNonConst()
264  {
265  return constraints_library_;
266  }
267 
268  const ConstraintsLibraryPtr& getConstraintsLibrary() const
269  {
270  return constraints_library_;
271  }
272 
273  bool simplifySolutions() const
274  {
275  return simplify_solutions_;
276  }
277 
278  void simplifySolutions(bool flag)
279  {
280  simplify_solutions_ = flag;
281  }
282 
283  void setInterpolation(bool flag)
284  {
285  interpolate_ = flag;
286  }
287 
288  void setHybridize(bool flag)
289  {
290  hybridize_ = flag;
291  }
292 
293  /* @brief Solve the planning problem. Return true if the problem is solved
294  @param timeout The time to spend on solving
295  @param count The number of runs to combine the paths of, in an attempt to generate better quality paths
296  */
297  const moveit_msgs::msg::MoveItErrorCodes solve(double timeout, unsigned int count);
298 
299  /* @brief Benchmark the planning problem. Return true on successful saving of benchmark results
300  @param timeout The time to spend on solving
301  @param count The number of runs to average in the computation of the benchmark
302  @param filename The name of the file to which the benchmark results are to be saved (automatic names can be
303  provided if a name is not specified)
304  */
305  bool benchmark(double timeout, unsigned int count, const std::string& filename = "");
306 
307  /* @brief Get the amount of time spent computing the last plan */
308  double getLastPlanTime() const
309  {
310  return last_plan_time_;
311  }
312 
313  /* @brief Get the amount of time spent simplifying the last plan */
314  double getLastSimplifyTime() const
315  {
316  return last_simplify_time_;
317  }
318 
319  /* @brief Apply smoothing and try to simplify the plan
320  @param timeout The amount of time allowed to be spent on simplifying the plan*/
321  void simplifySolution(double timeout);
322 
323  /* @brief Interpolate the solution*/
324  void interpolateSolution();
325 
326  /* @brief Get the solution as a RobotTrajectory object*/
328 
329  void convertPath(const og::PathGeometric& pg, robot_trajectory::RobotTrajectory& traj) const;
330 
333  bool loadConstraintApproximations(const rclcpp::Node::SharedPtr& node);
334 
337  bool saveConstraintApproximations(const rclcpp::Node::SharedPtr& node);
338 
346  virtual void configure(const rclcpp::Node::SharedPtr& node, bool use_constraints_approximations);
347 
348 protected:
349  void preSolve();
350  void postSolve();
351 
352  void startSampling();
353  void stopSampling();
354 
355  virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string& peval) const;
356  virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace* ss) const;
357  virtual void useConfig();
358  virtual ob::GoalPtr constructGoal();
359 
360  /* @brief Construct a planner termination condition, by default a simple time limit
361  @param timeout The maximum time (in seconds) that can be used for planning
362  @param start The point in time from which planning is considered to have started
363 
364  An additional planner termination condition can be specified per planner
365  configuration in ompl_planning.yaml via the `termination_condition` parameter.
366  Possible values are:
367 
368  * `Iteration[num]`: Terminate after `num` iterations. Here, `num` should be replaced
369  with a positive integer.
370  * `CostConvergence[solutions_window,epsilon]`: Terminate after the cost (as specified
371  by an optimization objective) has converged. The parameter `solutions_window`
372  specifies the minimum number of solutions to use in deciding whether a planner has
373  converged. The parameter `epsilon` is the threshold to consider for convergence.
374  This should be a positive number close to 0. If the cumulative moving average does
375  not change by a relative fraction of epsilon after a new better solution is found,
376  convergence has been reached.
377  * `ExactSolution`: Terminate as soon as an exact solution is found or a timeout
378  occurs. This modifies the behavior of anytime/optimizing planners to terminate
379  upon discovering the first feasible solution.
380 
381  In all cases, the planner will terminate when either the user-specified termination
382  condition is satisfied or the time limit specified by `timeout` has been reached,
383  whichever occurs first.
384  */
385  virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout,
386  const ompl::time::point& start);
387 
388  void registerTerminationCondition(const ob::PlannerTerminationCondition& ptc);
390 
392  int32_t logPlannerStatus(const og::SimpleSetupPtr& ompl_simple_setup);
393 
395 
397 
399  og::SimpleSetupPtr ompl_simple_setup_;
400 
402  ot::Benchmark ompl_benchmark_;
403 
405  ot::ParallelPlan ompl_parallel_plan_;
406 
407  std::vector<int> space_signature_;
408 
409  kinematic_constraints::KinematicConstraintSetPtr path_constraints_;
410  moveit_msgs::msg::Constraints path_constraints_msg_;
411  std::vector<kinematic_constraints::KinematicConstraintSetPtr> goal_constraints_;
412 
413  const ob::PlannerTerminationCondition* ptc_;
414  std::mutex ptc_lock_;
415 
418 
421 
424  unsigned int max_goal_samples_;
425 
429 
432 
434  unsigned int max_planning_threads_;
435 
439 
443 
446 
447  ConstraintsLibraryPtr constraints_library_;
448 
450 
451  // if false the final solution is not interpolated
453 
454  // if false parallel plan returns the first solution found
456 };
457 } // namespace ompl_interface
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const moveit::core::RobotModelConstPtr & getRobotModel() const
int32_t logPlannerStatus(const og::SimpleSetupPtr &ompl_simple_setup)
Convert OMPL PlannerStatus to moveit_msgs::msg::MoveItErrorCode.
virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string &peval) const
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
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...
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
virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout, const ompl::time::point &start)
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
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)
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_
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)
og::SimpleSetupPtr ompl_simple_setup_
the OMPL planning context; this contains the problem definition and the planner used
void setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters &wparams)
void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr &csm)
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
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
void setMinimumWaypointCount(unsigned int mwc)
Get the minimum number of waypoints along the solution path.
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
void setMaximumGoalSamples(unsigned int max_goal_samples)
ModelBasedPlanningContextSpecification spec_
void setSpecificationConfig(const std::map< std::string, std::string > &config)
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...
double last_simplify_time_
the time spent simplifying the last plan
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
name
Definition: setup.py:7
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ob::ConstrainedStateSpacePtr constrained_state_space_
OMPL constrained state space to handle path constraints.