moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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
42
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>
47#include <ompl/base/spaces/constraint/ConstrainedStateSpace.h>
48
49namespace ompl_interface
50{
51namespace ob = ompl::base;
52namespace og = ompl::geometric;
53namespace ot = ompl::tools;
54
55MOVEIT_CLASS_FORWARD(ModelBasedPlanningContext); // Defines ModelBasedPlanningContextPtr, ConstPtr, WeakPtr... etc
56MOVEIT_CLASS_FORWARD(ConstraintsLibrary); // Defines ConstraintsLibraryPtr, ConstPtr, WeakPtr... etc
57
59typedef std::function<ob::PlannerPtr(const ompl::base::SpaceInformationPtr& si, const std::string& name,
62typedef std::function<ConfiguredPlannerAllocator(const std::string& planner_type)> ConfiguredPlannerSelector;
63
65{
66 std::map<std::string, std::string> config_;
68 constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_;
69
70 ModelBasedStateSpacePtr state_space_;
71 og::SimpleSetupPtr ompl_simple_setup_; // pass in the correct simple setup type
72
84 ob::ConstrainedStateSpacePtr constrained_state_space_;
85};
86
88{
89public:
90 ModelBasedPlanningContext(const std::string& name, const ModelBasedPlanningContextSpecification& spec);
91
93 {
94 }
95
98
99 void clear() override;
100 bool terminate() override;
101
103 {
104 return spec_;
105 }
106
107 const std::map<std::string, std::string>& getSpecificationConfig() const
108 {
109 return spec_.config_;
110 }
111
112 void setSpecificationConfig(const std::map<std::string, std::string>& config)
113 {
114 spec_.config_ = config;
115 }
116
117 const moveit::core::RobotModelConstPtr& getRobotModel() const
118 {
119 return spec_.state_space_->getRobotModel();
120 }
121
123 {
124 return spec_.state_space_->getJointModelGroup();
125 }
126
131
132 const ModelBasedStateSpacePtr& getOMPLStateSpace() const
133 {
134 return spec_.state_space_;
135 }
136
137 const og::SimpleSetupPtr& getOMPLSimpleSetup() const
138 {
139 return ompl_simple_setup_;
140 }
141
142 og::SimpleSetupPtr& getOMPLSimpleSetup()
143 {
144 return ompl_simple_setup_;
145 }
146
147 const ot::Benchmark& getOMPLBenchmark() const
148 {
149 return ompl_benchmark_;
150 }
151
152 ot::Benchmark& getOMPLBenchmark()
153 {
154 return ompl_benchmark_;
155 }
156
157 const kinematic_constraints::KinematicConstraintSetPtr& getPathConstraints() const
158 {
159 return path_constraints_;
160 }
161
162 /* \brief Get the maximum number of sampling attempts allowed when sampling states is needed */
164 {
166 }
167
168 /* \brief Set the maximum number of sampling attempts allowed when sampling states is needed */
169 void setMaximumStateSamplingAttempts(unsigned int max_state_sampling_attempts)
170 {
171 max_state_sampling_attempts_ = max_state_sampling_attempts;
172 }
173
174 /* \brief Get the maximum number of sampling attempts allowed when sampling goals is needed */
176 {
178 }
179
180 /* \brief Set the maximum number of sampling attempts allowed when sampling goals is needed */
181 void setMaximumGoalSamplingAttempts(unsigned int max_goal_sampling_attempts)
182 {
183 max_goal_sampling_attempts_ = max_goal_sampling_attempts;
184 }
185
186 /* \brief Get the maximum number of valid goal samples to store */
187 unsigned int getMaximumGoalSamples() const
188 {
189 return max_goal_samples_;
190 }
191
192 /* \brief Set the maximum number of valid goal samples to store */
193 void setMaximumGoalSamples(unsigned int max_goal_samples)
194 {
195 max_goal_samples_ = max_goal_samples;
196 }
197
198 /* \brief Get the maximum number of planning threads allowed */
199 unsigned int getMaximumPlanningThreads() const
200 {
202 }
203
204 /* \brief Set the maximum number of planning threads */
205 void setMaximumPlanningThreads(unsigned int max_planning_threads)
206 {
207 max_planning_threads_ = max_planning_threads;
208 }
209
210 /* \brief Get the maximum solution segment length */
212 {
214 }
215
216 /* \brief Set the maximum solution segment length */
218 {
220 }
221
222 unsigned int getMinimumWaypointCount() const
223 {
225 }
226
228 void setMinimumWaypointCount(unsigned int mwc)
229 {
231 }
232
233 const constraint_samplers::ConstraintSamplerManagerPtr& getConstraintSamplerManager()
234 {
236 }
237
238 void setConstraintSamplerManager(const constraint_samplers::ConstraintSamplerManagerPtr& csm)
239 {
241 }
242
243 void setVerboseStateValidityChecks(bool flag);
244
245 void setProjectionEvaluator(const std::string& peval);
246
247 void setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters& wparams);
248
249 void setCompleteInitialState(const moveit::core::RobotState& complete_initial_robot_state);
250
251 bool setGoalConstraints(const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
252 const moveit_msgs::msg::Constraints& path_constraints,
253 moveit_msgs::msg::MoveItErrorCodes* error);
254 bool setPathConstraints(const moveit_msgs::msg::Constraints& path_constraints,
255 moveit_msgs::msg::MoveItErrorCodes* error);
256
257 void setConstraintsApproximations(const ConstraintsLibraryPtr& constraints_library)
258 {
259 constraints_library_ = constraints_library;
260 }
261
262 ConstraintsLibraryPtr getConstraintsLibraryNonConst()
263 {
265 }
266
267 const ConstraintsLibraryPtr& getConstraintsLibrary() const
268 {
270 }
271
272 bool simplifySolutions() const
273 {
274 return simplify_solutions_;
275 }
276
277 void simplifySolutions(bool flag)
278 {
279 simplify_solutions_ = flag;
280 }
281
282 void setInterpolation(bool flag)
283 {
284 interpolate_ = flag;
285 }
286
287 void setHybridize(bool flag)
288 {
289 hybridize_ = flag;
290 }
291
292 /* @brief Solve the planning problem. Return true if the problem is solved
293 @param timeout The time to spend on solving
294 @param count The number of runs to combine the paths of, in an attempt to generate better quality paths
295 */
296 const moveit_msgs::msg::MoveItErrorCodes solve(double timeout, unsigned int count);
297
298 /* @brief Benchmark the planning problem. Return true on successful saving of benchmark results
299 @param timeout The time to spend on solving
300 @param count The number of runs to average in the computation of the benchmark
301 @param filename The name of the file to which the benchmark results are to be saved (automatic names can be
302 provided if a name is not specified)
303 */
304 bool benchmark(double timeout, unsigned int count, const std::string& filename = "");
305
306 /* @brief Get the amount of time spent computing the last plan */
307 double getLastPlanTime() const
308 {
309 return last_plan_time_;
310 }
311
312 /* @brief Get the amount of time spent simplifying the last plan */
313 double getLastSimplifyTime() const
314 {
315 return last_simplify_time_;
316 }
317
318 /* @brief Apply smoothing and try to simplify the plan
319 @param timeout The amount of time allowed to be spent on simplifying the plan*/
320 void simplifySolution(double timeout);
321
322 /* @brief Interpolate the solution*/
323 void interpolateSolution();
324
325 /* @brief Get the solution as a RobotTrajectory object*/
327
328 void convertPath(const og::PathGeometric& pg, robot_trajectory::RobotTrajectory& traj) const;
329
332 bool loadConstraintApproximations(const rclcpp::Node::SharedPtr& node);
333
336 bool saveConstraintApproximations(const rclcpp::Node::SharedPtr& node);
337
345 virtual void configure(const rclcpp::Node::SharedPtr& node, bool use_constraints_approximations);
346
347protected:
348 void preSolve();
349 void postSolve();
350
351 void startSampling();
352 void stopSampling();
353
354 virtual ob::ProjectionEvaluatorPtr getProjectionEvaluator(const std::string& peval) const;
355 virtual ob::StateSamplerPtr allocPathConstrainedSampler(const ompl::base::StateSpace* ss) const;
356 virtual void useConfig();
357 virtual ob::GoalPtr constructGoal();
358
359 /* @brief Construct a planner termination condition, by default a simple time limit
360 @param timeout The maximum time (in seconds) that can be used for planning
361 @param start The point in time from which planning is considered to have started
362
363 An additional planner termination condition can be specified per planner
364 configuration in ompl_planning.yaml via the `termination_condition` parameter.
365 Possible values are:
366
367 * `Iteration[num]`: Terminate after `num` iterations. Here, `num` should be replaced
368 with a positive integer.
369 * `CostConvergence[solutions_window,epsilon]`: Terminate after the cost (as specified
370 by an optimization objective) has converged. The parameter `solutions_window`
371 specifies the minimum number of solutions to use in deciding whether a planner has
372 converged. The parameter `epsilon` is the threshold to consider for convergence.
373 This should be a positive number close to 0. If the cumulative moving average does
374 not change by a relative fraction of epsilon after a new better solution is found,
375 convergence has been reached.
376 * `ExactSolution`: Terminate as soon as an exact solution is found or a timeout
377 occurs. This modifies the behavior of anytime/optimizing planners to terminate
378 upon discovering the first feasible solution.
379
380 In all cases, the planner will terminate when either the user-specified termination
381 condition is satisfied or the time limit specified by `timeout` has been reached,
382 whichever occurs first.
383 */
384 virtual ob::PlannerTerminationCondition constructPlannerTerminationCondition(double timeout,
385 const ompl::time::point& start);
386
387 void registerTerminationCondition(const ob::PlannerTerminationCondition& ptc);
389
391 int32_t logPlannerStatus(const og::SimpleSetupPtr& ompl_simple_setup);
392
394
396
398 og::SimpleSetupPtr ompl_simple_setup_;
399
401 ot::Benchmark ompl_benchmark_;
402
404 ot::ParallelPlan ompl_parallel_plan_;
405
406 std::vector<int> space_signature_;
407
408 kinematic_constraints::KinematicConstraintSetPtr path_constraints_;
409 moveit_msgs::msg::Constraints path_constraints_msg_;
410 std::vector<kinematic_constraints::KinematicConstraintSetPtr> goal_constraints_;
411
412 const ob::PlannerTerminationCondition* ptc_;
413 std::mutex ptc_lock_;
414
417
420
423 unsigned int max_goal_samples_;
424
428
431
434
438
442
445
446 ConstraintsLibraryPtr constraints_library_;
447
449
450 // if false the final solution is not interpolated
452
453 // if false parallel plan returns the first solution found
455};
456} // namespace ompl_interface
#define MOVEIT_CLASS_FORWARD(C)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
const ConstraintsLibraryPtr & getConstraintsLibrary() 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_
const std::map< std::string, std::string > & getSpecificationConfig() const
unsigned int max_planning_threads_
when planning in parallel, this is the maximum number of threads to use at one time
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 ModelBasedPlanningContextSpecification & getSpecification() const
bool setPathConstraints(const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
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 moveit::core::RobotState & getCompleteInitialRobotState() 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 moveit::core::RobotModelConstPtr & getRobotModel() const
void convertPath(const og::PathGeometric &pg, robot_trajectory::RobotTrajectory &traj) const
std::vector< kinematic_constraints::KinematicConstraintSetPtr > goal_constraints_
const ModelBasedStateSpacePtr & getOMPLStateSpace() const
kinematic_constraints::KinematicConstraintSetPtr path_constraints_
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)
const moveit::core::JointModelGroup * getJointModelGroup() const
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
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.
void setMaximumGoalSamples(unsigned int max_goal_samples)
void solve(planning_interface::MotionPlanResponse &res) override
Solve the motion planning problem and store the result in res. This function should not clear data st...
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_...
const og::SimpleSetupPtr & getOMPLSimpleSetup() const
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintSamplerManager()
double last_simplify_time_
the time spent simplifying the last plan
void setConstraintsApproximations(const ConstraintsLibraryPtr &constraints_library)
const kinematic_constraints::KinematicConstraintSetPtr & getPathConstraints() const
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
std::function< ConfiguredPlannerAllocator(const std::string &planner_type)> ConfiguredPlannerSelector
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ob::ConstrainedStateSpacePtr constrained_state_space_
OMPL constrained state space to handle path constraints.
Response to a planning query.