moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
model_based_planning_context.cpp
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#include <boost/algorithm/string/trim.hpp>
38#include <boost/algorithm/string/split.hpp>
39#include <boost/algorithm/string/replace.hpp>
40#include <boost/lexical_cast.hpp>
41
49
51
54
55#include <ompl/config.h>
56#include <ompl/base/samplers/UniformValidStateSampler.h>
57#include <ompl/base/goals/GoalLazySamples.h>
58#include <ompl/tools/config/SelfConfig.h>
59#include <ompl/base/spaces/SE3StateSpace.h>
60#include <ompl/datastructures/PDF.h>
61#include <ompl/base/terminationconditions/IterationTerminationCondition.h>
62#include <ompl/base/terminationconditions/CostConvergenceTerminationCondition.h>
63
64#include <ompl/base/objectives/PathLengthOptimizationObjective.h>
65#include <ompl/base/objectives/MechanicalWorkOptimizationObjective.h>
66#include <ompl/base/objectives/MinimaxObjective.h>
67#include <ompl/base/objectives/StateCostIntegralObjective.h>
68#include <ompl/base/objectives/MaximizeMinClearanceObjective.h>
69#include <ompl/geometric/planners/prm/LazyPRM.h>
70
71namespace ompl_interface
72{
73namespace
74{
75rclcpp::Logger getLogger()
76{
77 return moveit::getLogger("moveit.planners.ompl.model_based_planning_context");
78}
79} // namespace
80
83 : planning_interface::PlanningContext(name, spec.state_space_->getJointModelGroup()->getName())
84 , spec_(spec)
85 , complete_initial_robot_state_(spec.state_space_->getRobotModel())
86 , ompl_simple_setup_(spec.ompl_simple_setup_)
87 , ompl_benchmark_(*ompl_simple_setup_)
88 , ompl_parallel_plan_(ompl_simple_setup_->getProblemDefinition())
89 , ptc_(nullptr)
90 , last_plan_time_(0.0)
91 , last_simplify_time_(0.0)
92 , max_goal_samples_(0)
93 , max_state_sampling_attempts_(0)
94 , max_goal_sampling_attempts_(0)
95 , max_planning_threads_(0)
96 , max_solution_segment_length_(0.0)
97 , minimum_waypoint_count_(0)
98 , multi_query_planning_enabled_(false) // maintain "old" behavior by default
99 , simplify_solutions_(true)
100 , interpolate_(true)
101 , hybridize_(true)
102{
103 complete_initial_robot_state_.setToDefaultValues(); // avoid uninitialized memory
105
106 constraints_library_ = std::make_shared<ConstraintsLibrary>(this);
107}
108
109void ModelBasedPlanningContext::configure(const rclcpp::Node::SharedPtr& node, bool use_constraints_approximations)
110{
112 if (!use_constraints_approximations)
113 {
114 setConstraintsApproximations(ConstraintsLibraryPtr());
115 }
117 ompl_simple_setup_->getStateSpace()->computeSignature(space_signature_);
118 ompl_simple_setup_->getStateSpace()->setStateSamplerAllocator(
119 [this](const ompl::base::StateSpace* ss) { return allocPathConstrainedSampler(ss); });
120
122 {
123 // convert the input state to the corresponding OMPL state
124 ompl::base::ScopedState<> ompl_start_state(spec_.constrained_state_space_);
125 spec_.state_space_->copyToOMPLState(ompl_start_state.get(), getCompleteInitialRobotState());
126 ompl_simple_setup_->setStartState(ompl_start_state);
127 ompl_simple_setup_->setStateValidityChecker(std::make_shared<ConstrainedPlanningStateValidityChecker>(this));
128 }
129 else
130 {
131 // convert the input state to the corresponding OMPL state
132 ompl::base::ScopedState<> ompl_start_state(spec_.state_space_);
133 spec_.state_space_->copyToOMPLState(ompl_start_state.get(), getCompleteInitialRobotState());
134 ompl_simple_setup_->setStartState(ompl_start_state);
135 ompl_simple_setup_->setStateValidityChecker(std::make_shared<StateValidityChecker>(this));
136 }
137
139 {
140 const ConstraintApproximationPtr& constraint_approx =
141 constraints_library_->getConstraintApproximation(path_constraints_msg_);
142 if (constraint_approx)
143 {
144 getOMPLStateSpace()->setInterpolationFunction(constraint_approx->getInterpolationFunction());
145 RCLCPP_INFO(getLogger(), "Using precomputed interpolation states");
146 }
147 }
148
149 useConfig();
150 if (ompl_simple_setup_->getGoal())
151 ompl_simple_setup_->setup();
152}
153
155{
156 if (!spec_.state_space_)
157 {
158 RCLCPP_ERROR(getLogger(), "No state space is configured yet");
159 return;
160 }
161 ob::ProjectionEvaluatorPtr projection_eval = getProjectionEvaluator(peval);
162 if (projection_eval)
163 spec_.state_space_->registerDefaultProjection(projection_eval);
164}
165
166ompl::base::ProjectionEvaluatorPtr ModelBasedPlanningContext::getProjectionEvaluator(const std::string& peval) const
167{
168 if (peval.find_first_of("link(") == 0 && peval[peval.length() - 1] == ')')
169 {
170 std::string link_name = peval.substr(5, peval.length() - 6);
171 if (getRobotModel()->hasLinkModel(link_name))
172 {
173 return std::make_shared<ProjectionEvaluatorLinkPose>(this, link_name);
174 }
175 else
176 {
177 RCLCPP_ERROR(getLogger(),
178 "Attempted to set projection evaluator with respect to position of link '%s', "
179 "but that link is not known to the kinematic model.",
180 link_name.c_str());
181 }
182 }
183 else if (peval.find_first_of("joints(") == 0 && peval[peval.length() - 1] == ')')
184 {
185 std::string joints = peval.substr(7, peval.length() - 8);
186 boost::replace_all(joints, ",", " ");
187 std::vector<unsigned int> j;
188 std::stringstream ss(joints);
189 while (ss.good() && !ss.eof())
190 {
191 std::string joint;
192 ss >> joint >> std::ws;
193 if (getJointModelGroup()->hasJointModel(joint))
194 {
195 unsigned int variable_count = getJointModelGroup()->getJointModel(joint)->getVariableCount();
196 if (variable_count > 0)
197 {
198 int idx = getJointModelGroup()->getVariableGroupIndex(joint);
199 for (unsigned int q = 0; q < variable_count; ++q)
200 {
201 j.push_back(idx + q);
202 }
203 }
204 else
205 {
206 RCLCPP_WARN(getLogger(), "%s: Ignoring joint '%s' in projection since it has 0 DOF", name_.c_str(),
207 joint.c_str());
208 }
209 }
210 else
211 {
212 RCLCPP_ERROR(getLogger(),
213 "%s: Attempted to set projection evaluator with respect to value of joint "
214 "'%s', but that joint is not known to the group '%s'.",
215 name_.c_str(), joint.c_str(), getGroupName().c_str());
216 }
217 }
218 if (j.empty())
219 {
220 RCLCPP_ERROR(getLogger(), "%s: No valid joints specified for joint projection", name_.c_str());
221 }
222 else
223 {
224 return std::make_shared<ProjectionEvaluatorJointValue>(this, j);
225 }
226 }
227 else
228 {
229 RCLCPP_ERROR(getLogger(), "Unable to allocate projection evaluator based on description: '%s'", peval.c_str());
230 }
231 return ob::ProjectionEvaluatorPtr();
232}
233
234ompl::base::StateSamplerPtr
235ModelBasedPlanningContext::allocPathConstrainedSampler(const ompl::base::StateSpace* state_space) const
236{
237 if (spec_.state_space_.get() != state_space)
238 {
239 RCLCPP_ERROR(getLogger(), "%s: Attempted to allocate a state sampler for an unknown state space", name_.c_str());
240 return ompl::base::StateSamplerPtr();
241 }
242
243 RCLCPP_DEBUG(getLogger(), "%s: Allocating a new state sampler (attempts to use path constraints)", name_.c_str());
244
246 {
248 {
249 const ConstraintApproximationPtr& constraint_approx =
250 constraints_library_->getConstraintApproximation(path_constraints_msg_);
251 if (constraint_approx)
252 {
253 ompl::base::StateSamplerAllocator state_sampler_allocator =
254 constraint_approx->getStateSamplerAllocator(path_constraints_msg_);
255 if (state_sampler_allocator)
256 {
257 ompl::base::StateSamplerPtr state_sampler = state_sampler_allocator(state_space);
258 if (state_sampler)
259 {
260 RCLCPP_INFO(getLogger(),
261 "%s: Using precomputed state sampler (approximated constraint space) for constraint '%s'",
262 name_.c_str(), path_constraints_msg_.name.c_str());
263 return state_sampler;
264 }
265 }
266 }
267 }
268
269 constraint_samplers::ConstraintSamplerPtr constraint_sampler;
271 {
272 constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
273 path_constraints_->getAllConstraints());
274 }
275
276 if (constraint_sampler)
277 {
278 RCLCPP_INFO(getLogger(), "%s: Allocating specialized state sampler for state space", name_.c_str());
279 return std::make_shared<ConstrainedSampler>(this, constraint_sampler);
280 }
281 }
282 RCLCPP_DEBUG(getLogger(), "%s: Allocating default state sampler for state space", name_.c_str());
283 return state_space->allocDefaultStateSampler();
284}
285
287{
288 const std::map<std::string, std::string>& config = spec_.config_;
289 if (config.empty())
290 return;
291 std::map<std::string, std::string> cfg = config;
292
293 // set the distance between waypoints when interpolating and collision checking.
294 auto it = cfg.find("longest_valid_segment_fraction");
295 // If one of the two variables is set.
296 if (it != cfg.end() || max_solution_segment_length_ != 0.0)
297 {
298 // clang-format off
299 double longest_valid_segment_fraction_config = (it != cfg.end())
300 ? moveit::core::toDouble(it->second) // value from config file if there
301 : 0.01; // default value in OMPL.
302 double longest_valid_segment_fraction_final = longest_valid_segment_fraction_config;
304 {
305 // If this parameter is specified too, take the most conservative of the two variables,
306 // i.e. the one that uses the shorter segment length.
307 longest_valid_segment_fraction_final = std::min(
308 longest_valid_segment_fraction_config,
310 );
311 }
312 // clang-format on
313
314 // convert to string using no locale
315 cfg["longest_valid_segment_fraction"] = moveit::core::toString(longest_valid_segment_fraction_final);
316 }
317
318 // set the projection evaluator
319 it = cfg.find("projection_evaluator");
320 if (it != cfg.end())
321 {
322 setProjectionEvaluator(boost::trim_copy(it->second));
323 cfg.erase(it);
324 }
325
326 if (cfg.empty())
327 {
328 return;
329 }
330
331 std::string optimizer;
332 ompl::base::OptimizationObjectivePtr objective;
333 it = cfg.find("optimization_objective");
334 if (it != cfg.end())
335 {
336 optimizer = it->second;
337 cfg.erase(it);
338
339 if (optimizer == "PathLengthOptimizationObjective")
340 {
341 objective =
342 std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
343 }
344 else if (optimizer == "MinimaxObjective")
345 {
346 objective = std::make_shared<ompl::base::MinimaxObjective>(ompl_simple_setup_->getSpaceInformation());
347 }
348 else if (optimizer == "StateCostIntegralObjective")
349 {
350 objective = std::make_shared<ompl::base::StateCostIntegralObjective>(ompl_simple_setup_->getSpaceInformation());
351 }
352 else if (optimizer == "MechanicalWorkOptimizationObjective")
353 {
354 objective =
355 std::make_shared<ompl::base::MechanicalWorkOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
356 }
357 else if (optimizer == "MaximizeMinClearanceObjective")
358 {
359 objective =
360 std::make_shared<ompl::base::MaximizeMinClearanceObjective>(ompl_simple_setup_->getSpaceInformation());
361 }
362 else
363 {
364 RCLCPP_WARN(getLogger(),
365 "Optimization objective %s is invalid or not defined, using PathLengthOptimizationObjective instead",
366 optimizer.c_str());
367 objective =
368 std::make_shared<ompl::base::PathLengthOptimizationObjective>(ompl_simple_setup_->getSpaceInformation());
369 }
370
371 ompl_simple_setup_->setOptimizationObjective(objective);
372 }
373
374 // Don't clear planner data if multi-query planning is enabled
375 it = cfg.find("multi_query_planning_enabled");
376 if (it != cfg.end())
377 {
378 multi_query_planning_enabled_ = boost::lexical_cast<bool>(it->second);
379 }
380
381 // check whether the path returned by the planner should be interpolated
382 it = cfg.find("interpolate");
383 if (it != cfg.end())
384 {
385 interpolate_ = boost::lexical_cast<bool>(it->second);
386 cfg.erase(it);
387 }
388
389 // check whether the path returned by the planner should be simplified
390 it = cfg.find("simplify_solutions");
391 if (it != cfg.end())
392 {
393 simplify_solutions_ = boost::lexical_cast<bool>(it->second);
394 cfg.erase(it);
395 }
396
397 // check whether solution paths from parallel planning should be hybridized
398 it = cfg.find("hybridize");
399 if (it != cfg.end())
400 {
401 hybridize_ = boost::lexical_cast<bool>(it->second);
402 cfg.erase(it);
403 }
404
405 // remove the 'type' parameter; the rest are parameters for the planner itself
406 it = cfg.find("type");
407 if (it == cfg.end())
408 {
409 if (name_ != getGroupName())
410 RCLCPP_WARN(getLogger(), "%s: Attribute 'type' not specified in planner configuration", name_.c_str());
411 }
412 else
413 {
414 std::string type = it->second;
415 cfg.erase(it);
416 const std::string planner_name = getGroupName() + "/" + name_;
417 ompl_simple_setup_->setPlannerAllocator(
418 [planner_name, &spec = spec_, allocator = spec_.planner_selector_(type)](
419 const ompl::base::SpaceInformationPtr& si) { return allocator(si, planner_name, spec); });
420 RCLCPP_INFO(getLogger(),
421 "Planner configuration '%s' will use planner '%s'. "
422 "Additional configuration parameters will be set when the planner is constructed.",
423 name_.c_str(), type.c_str());
424 }
425
426 // call the setParams() after setup(), so we know what the params are
427 ompl_simple_setup_->getSpaceInformation()->setup();
428 ompl_simple_setup_->getSpaceInformation()->params().setParams(cfg, true);
429 // call setup() again for possibly new param values
430 ompl_simple_setup_->getSpaceInformation()->setup();
431}
432
433void ModelBasedPlanningContext::setPlanningVolume(const moveit_msgs::msg::WorkspaceParameters& wparams)
434{
435 if (wparams.min_corner.x == wparams.max_corner.x && wparams.min_corner.x == 0.0 &&
436 wparams.min_corner.y == wparams.max_corner.y && wparams.min_corner.y == 0.0 &&
437 wparams.min_corner.z == wparams.max_corner.z && wparams.min_corner.z == 0.0)
438 {
439 RCLCPP_WARN(getLogger(), "It looks like the planning volume was not specified.");
440 }
441
442 RCLCPP_DEBUG(getLogger(),
443 "%s: Setting planning volume (affects SE2 & SE3 joints only) to x = [%f, %f], y = "
444 "[%f, %f], z = [%f, %f]",
445 name_.c_str(), wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y, wparams.max_corner.y,
446 wparams.min_corner.z, wparams.max_corner.z);
447
448 spec_.state_space_->setPlanningVolume(wparams.min_corner.x, wparams.max_corner.x, wparams.min_corner.y,
449 wparams.max_corner.y, wparams.min_corner.z, wparams.max_corner.z);
450}
451
453{
454 ompl::time::point start = ompl::time::now();
455 ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
457 ompl_simple_setup_->simplifySolution(ptc);
458 last_simplify_time_ = ompl_simple_setup_->getLastSimplificationTime();
460}
461
463{
464 if (ompl_simple_setup_->haveSolutionPath())
465 {
466 og::PathGeometric& pg = ompl_simple_setup_->getSolutionPath();
467
468 // Find the number of states that will be in the interpolated solution.
469 // This is what interpolate() does internally.
470 unsigned int eventual_states = 1;
471 std::vector<ompl::base::State*> states = pg.getStates();
472 for (size_t i = 0; i < states.size() - 1; ++i)
473 {
474 eventual_states += ompl_simple_setup_->getStateSpace()->validSegmentCount(states[i], states[i + 1]);
475 }
476
477 if (eventual_states < minimum_waypoint_count_)
478 {
479 // If that's not enough states, use the minimum amount instead.
480 pg.interpolate(minimum_waypoint_count_);
481 }
482 else
483 {
484 // Interpolate the path to have as the exact states that are checked when validating motions.
485 pg.interpolate();
486 }
487 }
488}
489
490void ModelBasedPlanningContext::convertPath(const ompl::geometric::PathGeometric& pg,
492{
494 for (std::size_t i = 0; i < pg.getStateCount(); ++i)
495 {
496 spec_.state_space_->copyToRobotState(ks, pg.getState(i));
497 traj.addSuffixWayPoint(ks, 0.0);
498 }
499}
500
502{
503 traj.clear();
504 if (ompl_simple_setup_->haveSolutionPath())
505 {
506 convertPath(ompl_simple_setup_->getSolutionPath(), traj);
507 }
508 return ompl_simple_setup_->haveSolutionPath();
509}
510
512{
513 if (ompl_simple_setup_->getStateValidityChecker())
514 {
515 static_cast<StateValidityChecker*>(ompl_simple_setup_->getStateValidityChecker().get())->setVerbose(flag);
516 }
517}
518
520{
521 // ******************* set up the goal representation, based on goal constraints
522
523 std::vector<ob::GoalPtr> goals;
524 for (kinematic_constraints::KinematicConstraintSetPtr& goal_constraint : goal_constraints_)
525 {
526 constraint_samplers::ConstraintSamplerPtr constraint_sampler;
528 {
529 constraint_sampler = spec_.constraint_sampler_manager_->selectSampler(getPlanningScene(), getGroupName(),
530 goal_constraint->getAllConstraints());
531 }
532
533 if (constraint_sampler)
534 {
535 ob::GoalPtr goal = std::make_shared<ConstrainedGoalSampler>(this, goal_constraint, constraint_sampler);
536 goals.push_back(goal);
537 }
538 }
539
540 if (!goals.empty())
541 {
542 return goals.size() == 1 ? goals[0] : std::make_shared<GoalSampleableRegionMux>(goals);
543 }
544 else
545 {
546 RCLCPP_ERROR(getLogger(), "Unable to construct goal representation");
547 }
548
549 return ob::GoalPtr();
550}
551
552ompl::base::PlannerTerminationCondition
553ModelBasedPlanningContext::constructPlannerTerminationCondition(double timeout, const ompl::time::point& start)
554{
555 auto it = spec_.config_.find("termination_condition");
556 if (it == spec_.config_.end())
557 {
558 return ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start));
559 }
560
561 std::string termination_string = it->second;
562 std::vector<std::string> termination_and_params;
563 boost::split(termination_and_params, termination_string, boost::is_any_of("[ ,]"));
564
565 if (termination_and_params.empty())
566 {
567 RCLCPP_ERROR(getLogger(), "Termination condition not specified");
568 }
569
570 // Terminate if a maximum number of iterations is exceeded or a timeout occurs.
571 // The semantics of "iterations" are planner-specific, but typically it corresponds to the number of times
572 // an attempt was made to grow a roadmap/tree.
573 else if (termination_and_params[0] == "Iteration")
574 {
575 if (termination_and_params.size() > 1)
576 {
577 return ob::plannerOrTerminationCondition(
578 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
579 ob::IterationTerminationCondition(std::stoul(termination_and_params[1])));
580 }
581 else
582 {
583 RCLCPP_ERROR(getLogger(), "Missing argument to Iteration termination condition");
584 }
585 }
586 // Terminate if the cost has converged or a timeout occurs.
587 // Only useful for anytime/optimizing planners.
588 else if (termination_and_params[0] == "CostConvergence")
589 {
590 std::size_t solutions_window = 10u;
591 double epsilon = 0.1;
592 if (termination_and_params.size() > 1)
593 {
594 solutions_window = std::stoul(termination_and_params[1]);
595 if (termination_and_params.size() > 2)
596 {
597 epsilon = moveit::core::toDouble(termination_and_params[2]);
598 }
599 }
600 return ob::plannerOrTerminationCondition(
601 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
602 ob::CostConvergenceTerminationCondition(ompl_simple_setup_->getProblemDefinition(), solutions_window, epsilon));
603 }
604 // Terminate as soon as an exact solution is found or a timeout occurs.
605 // This modifies the behavior of anytime/optimizing planners to terminate upon discovering
606 // the first feasible solution.
607 else if (termination_and_params[0] == "ExactSolution")
608 {
609 return ob::plannerOrTerminationCondition(
610 ob::timedPlannerTerminationCondition(timeout - ompl::time::seconds(ompl::time::now() - start)),
611 ob::exactSolnPlannerTerminationCondition(ompl_simple_setup_->getProblemDefinition()));
612 }
613 else
614 {
615 RCLCPP_ERROR(getLogger(), "Unknown planner termination condition");
616 }
617 // return a planner termination condition to suppress compiler warning
618 return ob::plannerAlwaysTerminatingCondition();
619}
620
622{
623 complete_initial_robot_state_ = complete_initial_robot_state;
625}
626
628{
630 {
631 ompl_simple_setup_->clear();
632 }
633 else
634 {
635 // For LazyPRM and LazyPRMstar we assume that the environment *could* have changed
636 // This means that we need to reset the validity flags for every node and edge in
637 // the roadmap. For PRM and PRMstar we assume that the environment is static. If
638 // this is not the case, then multi-query planning should not be enabled.
639 auto planner = dynamic_cast<ompl::geometric::LazyPRM*>(ompl_simple_setup_->getPlanner().get());
640 if (planner != nullptr)
641 {
642 planner->clearValidity();
643 }
644 }
645 ompl_simple_setup_->clearStartStates();
646 ompl_simple_setup_->setGoal(ob::GoalPtr());
647 ompl_simple_setup_->setStateValidityChecker(ob::StateValidityCheckerPtr());
648 path_constraints_.reset();
649 goal_constraints_.clear();
650 getOMPLStateSpace()->setInterpolationFunction(InterpolationFunction());
651}
652
653bool ModelBasedPlanningContext::setPathConstraints(const moveit_msgs::msg::Constraints& path_constraints,
654 moveit_msgs::msg::MoveItErrorCodes* /*error*/)
655{
656 // ******************* set the path constraints to use
657 path_constraints_ = std::make_shared<kinematic_constraints::KinematicConstraintSet>(getRobotModel());
658 path_constraints_->add(path_constraints, getPlanningScene()->getTransforms());
659 path_constraints_msg_ = path_constraints;
660
661 return true;
662}
663
664bool ModelBasedPlanningContext::setGoalConstraints(const std::vector<moveit_msgs::msg::Constraints>& goal_constraints,
665 const moveit_msgs::msg::Constraints& path_constraints,
666 moveit_msgs::msg::MoveItErrorCodes* error)
667{
668 // ******************* check if the input is correct
669 goal_constraints_.clear();
670 for (const moveit_msgs::msg::Constraints& goal_constraint : goal_constraints)
671 {
672 moveit_msgs::msg::Constraints constr = kinematic_constraints::mergeConstraints(goal_constraint, path_constraints);
673 kinematic_constraints::KinematicConstraintSetPtr kset(
675 kset->add(constr, getPlanningScene()->getTransforms());
676 if (!kset->empty())
677 {
678 goal_constraints_.push_back(kset);
679 }
680 }
681
682 if (goal_constraints_.empty())
683 {
684 RCLCPP_WARN(getLogger(), "%s: No goal constraints specified. There is no problem to solve.", name_.c_str());
685 if (error)
686 {
687 error->val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS;
688 }
689 return false;
690 }
691
692 ob::GoalPtr goal = constructGoal();
693 ompl_simple_setup_->setGoal(goal);
694 return static_cast<bool>(goal);
695}
696
697bool ModelBasedPlanningContext::benchmark(double timeout, unsigned int count, const std::string& filename)
698{
699 ompl_benchmark_.clearPlanners();
700 ompl_simple_setup_->setup();
701 ompl_benchmark_.addPlanner(ompl_simple_setup_->getPlanner());
702 ompl_benchmark_.setExperimentName(getRobotModel()->getName() + "_" + getGroupName() + "_" +
703 getPlanningScene()->getName() + "_" + name_);
704
705 ot::Benchmark::Request req;
706 req.maxTime = timeout;
707 req.runCount = count;
708 req.displayProgress = true;
709 req.saveConsoleOutput = false;
710 ompl_benchmark_.benchmark(req);
711 return filename.empty() ? ompl_benchmark_.saveResultsToFile() : ompl_benchmark_.saveResultsToFile(filename.c_str());
712}
713
715{
716 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
717 if (gls)
718 {
719 static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->startSampling();
720 }
721 else
722 {
723 // we know this is a GoalSampleableMux by elimination
724 static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->startSampling();
725 }
726}
727
729{
730 bool gls = ompl_simple_setup_->getGoal()->hasType(ob::GOAL_LAZY_SAMPLES);
731 if (gls)
732 {
733 static_cast<ob::GoalLazySamples*>(ompl_simple_setup_->getGoal().get())->stopSampling();
734 }
735 else
736 {
737 // we know this is a GoalSampleableMux by elimination
738 static_cast<GoalSampleableRegionMux*>(ompl_simple_setup_->getGoal().get())->stopSampling();
739 }
740}
741
743{
744 // clear previously computed solutions
745 ompl_simple_setup_->getProblemDefinition()->clearSolutionPaths();
746 const ob::PlannerPtr planner = ompl_simple_setup_->getPlanner();
747 if (planner && !multi_query_planning_enabled_)
748 {
749 planner->clear();
750 }
752 ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->resetMotionCounter();
753}
754
756{
757 stopSampling();
758 int v = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getValidMotionCount();
759 int iv = ompl_simple_setup_->getSpaceInformation()->getMotionValidator()->getInvalidMotionCount();
760 RCLCPP_DEBUG(getLogger(), "There were %d valid motions and %d invalid motions.", v, iv);
761
762 // Debug OMPL setup and solution
763 RCLCPP_DEBUG(getLogger(), "%s",
764 [&] {
765 std::stringstream debug_out;
766 ompl_simple_setup_->print(debug_out);
767 return debug_out.str();
768 }()
769 .c_str());
770}
771
773{
774 res.planner_id = request_.planner_id;
775 res.error_code = solve(request_.allowed_planning_time, request_.num_planning_attempts);
776 if (res.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
777 {
778 RCLCPP_ERROR(getLogger(), "Unable to solve the planning problem");
779 return;
780 }
781 double ptime = getLastPlanTime();
783 {
784 simplifySolution(request_.allowed_planning_time - ptime);
785 ptime += getLastSimplifyTime();
786 }
787
788 if (interpolate_)
789 {
791 }
792
793 // fill the response
794 RCLCPP_DEBUG(getLogger(), "%s: Returning successful solution with %lu states", getName().c_str(),
795 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
796
797 res.trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
799 res.planning_time = ptime;
800}
801
803{
804 res.planner_id = request_.planner_id;
805 res.error_code = solve(request_.allowed_planning_time, request_.num_planning_attempts);
806 if (res.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
807 {
808 RCLCPP_INFO(getLogger(), "Unable to solve the planning problem");
809 return;
810 }
811
812 res.trajectory.reserve(3);
813
814 // add info about planned solution
815 double ptime = getLastPlanTime();
816 res.processing_time.push_back(ptime);
817 res.description.emplace_back("plan");
818 res.trajectory.resize(res.trajectory.size() + 1);
819 res.trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
820 getSolutionPath(*res.trajectory.back());
821
822 // simplify solution if time remains
824 {
825 simplifySolution(request_.allowed_planning_time - ptime);
826 res.processing_time.push_back(getLastSimplifyTime());
827 res.description.emplace_back("simplify");
828 res.trajectory.resize(res.trajectory.size() + 1);
829 res.trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
830 getSolutionPath(*res.trajectory.back());
831 }
832
833 if (interpolate_)
834 {
835 ompl::time::point start_interpolate = ompl::time::now();
837 res.processing_time.push_back(ompl::time::seconds(ompl::time::now() - start_interpolate));
838 res.description.emplace_back("interpolate");
839 res.trajectory.resize(res.trajectory.size() + 1);
840 res.trajectory.back() = std::make_shared<robot_trajectory::RobotTrajectory>(getRobotModel(), getGroupName());
841 getSolutionPath(*res.trajectory.back());
842 }
843
844 RCLCPP_DEBUG(getLogger(), "%s: Returning successful solution with %lu states", getName().c_str(),
845 getOMPLSimpleSetup()->getSolutionPath().getStateCount());
846}
847
848const moveit_msgs::msg::MoveItErrorCodes ModelBasedPlanningContext::solve(double timeout, unsigned int count)
849{
850 ompl::time::point start = ompl::time::now();
851 preSolve();
852
853 moveit_msgs::msg::MoveItErrorCodes result;
854 result.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
855 if (count <= 1 || multi_query_planning_enabled_) // multi-query planners should always run in single instances
856 {
857 RCLCPP_DEBUG(getLogger(), "%s: Solving the planning problem once...", name_.c_str());
858 ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
860 std::ignore = ompl_simple_setup_->solve(ptc);
861 last_plan_time_ = ompl_simple_setup_->getLastPlanComputationTime();
863 // fill the result status code
865 }
866 else
867 {
868 RCLCPP_DEBUG(getLogger(), "%s: Solving the planning problem %u times...", name_.c_str(), count);
869 ompl_parallel_plan_.clearHybridizationPaths();
870 if (count <= max_planning_threads_)
871 {
872 ompl_parallel_plan_.clearPlanners();
873 if (ompl_simple_setup_->getPlannerAllocator())
874 {
875 for (unsigned int i = 0; i < count; ++i)
876 {
877 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
878 }
879 }
880 else
881 {
882 for (unsigned int i = 0; i < count; ++i)
883 {
884 ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
885 }
886 }
887
888 ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
890 if (ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION)
891 {
892 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
893 }
894 last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
896 }
897 else
898 {
899 ob::PlannerTerminationCondition ptc = constructPlannerTerminationCondition(timeout, start);
901 int n = count / max_planning_threads_;
902 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
903 for (int i = 0; i < n && !ptc(); ++i)
904 {
905 ompl_parallel_plan_.clearPlanners();
906 if (ompl_simple_setup_->getPlannerAllocator())
907 {
908 for (unsigned int i = 0; i < max_planning_threads_; ++i)
909 {
910 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
911 }
912 }
913 else
914 {
915 for (unsigned int i = 0; i < max_planning_threads_; ++i)
916 {
917 ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
918 }
919 }
920
921 bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
922 // Was this latest call successful too?
923 result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
924 moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
925 moveit_msgs::msg::MoveItErrorCodes::FAILURE;
926 }
927 n = count % max_planning_threads_;
928 if (n && !ptc())
929 {
930 ompl_parallel_plan_.clearPlanners();
931 if (ompl_simple_setup_->getPlannerAllocator())
932 {
933 for (int i = 0; i < n; ++i)
934 {
935 ompl_parallel_plan_.addPlannerAllocator(ompl_simple_setup_->getPlannerAllocator());
936 }
937 }
938 else
939 {
940 for (int i = 0; i < n; ++i)
941 {
942 ompl_parallel_plan_.addPlanner(ompl::tools::SelfConfig::getDefaultPlanner(ompl_simple_setup_->getGoal()));
943 }
944 }
945
946 bool r = ompl_parallel_plan_.solve(ptc, 1, count, hybridize_) == ompl::base::PlannerStatus::EXACT_SOLUTION;
947 // Was this latest call successful too?
948 result.val = (result.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS && r) ?
949 moveit_msgs::msg::MoveItErrorCodes::SUCCESS :
950 moveit_msgs::msg::MoveItErrorCodes::FAILURE;
951 }
952 last_plan_time_ = ompl::time::seconds(ompl::time::now() - start);
954 }
955 }
956
957 postSolve();
958 return result;
959}
960
961void ModelBasedPlanningContext::registerTerminationCondition(const ob::PlannerTerminationCondition& ptc)
962{
963 std::unique_lock<std::mutex> slock(ptc_lock_);
964 ptc_ = &ptc;
965}
966
968{
969 std::unique_lock<std::mutex> slock(ptc_lock_);
970 ptc_ = nullptr;
971}
972
973int32_t ModelBasedPlanningContext::logPlannerStatus(const og::SimpleSetupPtr& ompl_simple_setup)
974{
975 auto result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
976 const ompl::base::PlannerStatus ompl_status = ompl_simple_setup->getLastPlannerStatus();
977 switch (ompl::base::PlannerStatus::StatusType(ompl_status))
978 {
979 case ompl::base::PlannerStatus::UNKNOWN:
980 RCLCPP_WARN(getLogger(), "Motion planning failed for an unknown reason");
981 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
982 break;
983 case ompl::base::PlannerStatus::INVALID_START:
984 RCLCPP_WARN(getLogger(), "Invalid start state");
985 result = moveit_msgs::msg::MoveItErrorCodes::START_STATE_INVALID;
986 break;
987 case ompl::base::PlannerStatus::INVALID_GOAL:
988 RCLCPP_WARN(getLogger(), "Invalid goal state");
989 result = moveit_msgs::msg::MoveItErrorCodes::GOAL_STATE_INVALID;
990 break;
991 case ompl::base::PlannerStatus::UNRECOGNIZED_GOAL_TYPE:
992 RCLCPP_WARN(getLogger(), "Unrecognized goal type");
993 result = moveit_msgs::msg::MoveItErrorCodes::UNRECOGNIZED_GOAL_TYPE;
994 break;
995 case ompl::base::PlannerStatus::TIMEOUT:
996 RCLCPP_WARN(getLogger(), "Timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
997 request_.allowed_planning_time);
998 result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
999 break;
1000 case ompl::base::PlannerStatus::APPROXIMATE_SOLUTION:
1001 // timeout is a common reason for APPROXIMATE_SOLUTION
1002 if (ompl_simple_setup->getLastPlanComputationTime() > request_.allowed_planning_time)
1003 {
1004 RCLCPP_WARN(getLogger(), "Planning timed out: %.1fs ≥ %.1fs", ompl_simple_setup->getLastPlanComputationTime(),
1005 request_.allowed_planning_time);
1006 result = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
1007 }
1008 else
1009 {
1010 RCLCPP_WARN(getLogger(), "Solution is approximate");
1011 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1012 }
1013 break;
1014 case ompl::base::PlannerStatus::EXACT_SOLUTION:
1015 result = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
1016 break;
1017 case ompl::base::PlannerStatus::CRASH:
1018 RCLCPP_WARN(getLogger(), "OMPL crashed!");
1019 result = moveit_msgs::msg::MoveItErrorCodes::CRASH;
1020 break;
1021 case ompl::base::PlannerStatus::ABORT:
1022 RCLCPP_WARN(getLogger(), "OMPL was aborted");
1023 result = moveit_msgs::msg::MoveItErrorCodes::ABORT;
1024 break;
1025 default:
1026 // This should never happen
1027 RCLCPP_WARN(getLogger(), "Unexpected PlannerStatus code from OMPL.");
1028 result = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
1029 }
1030 return result;
1031}
1032
1034{
1035 std::unique_lock<std::mutex> slock(ptc_lock_);
1036 if (ptc_)
1037 {
1038 ptc_->terminate();
1039 }
1040 return true;
1041}
1042
1043bool ModelBasedPlanningContext::saveConstraintApproximations(const rclcpp::Node::SharedPtr& node)
1044{
1045 std::string constraint_path;
1046 if (node->get_parameter("constraint_approximations_path", constraint_path))
1047 {
1048 constraints_library_->saveConstraintApproximations(constraint_path);
1049 return true;
1050 }
1051 RCLCPP_WARN(getLogger(), "ROS param 'constraint_approximations' not found. Unable to save constraint approximations");
1052 return false;
1053}
1054
1055bool ModelBasedPlanningContext::loadConstraintApproximations(const rclcpp::Node::SharedPtr& node)
1056{
1057 std::string constraint_path;
1058 if (node->get_parameter("constraint_approximations_path", constraint_path))
1059 {
1060 constraints_library_->loadConstraintApproximations(constraint_path);
1061 std::stringstream ss;
1062 constraints_library_->printConstraintApproximations(ss);
1063 RCLCPP_INFO_STREAM(getLogger(), ss.str());
1064 return true;
1065 }
1066 return false;
1067}
1068
1069} // namespace ompl_interface
A class that contains many different constraints, and can check RobotState *versus the full set....
const JointModel * getJointModel(const std::string &joint) const
Get a joint by its name. Throw an exception if the joint is not part of this group.
int getVariableGroupIndex(const std::string &variable) const
Get the index of a variable within the group. Return -1 on error.
std::size_t getVariableCount() const
Get the number of variables that describe this joint.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
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
bool loadConstraintApproximations(const rclcpp::Node::SharedPtr &node)
Look up param server 'constraint_approximations' and use its value as the path to load constraint app...
bool setPathConstraints(const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
ModelBasedPlanningContext(const std::string &name, const ModelBasedPlanningContextSpecification &spec)
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_.
bool setGoalConstraints(const std::vector< moveit_msgs::msg::Constraints > &goal_constraints, const moveit_msgs::msg::Constraints &path_constraints, moveit_msgs::msg::MoveItErrorCodes *error)
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_
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)
const moveit::core::JointModelGroup * getJointModelGroup() const
ot::Benchmark ompl_benchmark_
the OMPL tool for benchmarking planners
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 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_
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
double last_simplify_time_
the time spent simplifying the last plan
void setConstraintsApproximations(const ConstraintsLibraryPtr &constraints_library)
An interface for a OMPL state validity checker.
std::string name_
The name of this planning context.
MotionPlanRequest request_
The planning request for this context.
const planning_scene::PlanningSceneConstPtr & getPlanningScene() const
Get the planning scene associated to this planning context.
const std::string & getGroupName() const
Get the name of the group this planning context is for.
const std::string & getName() const
Get the name of this planning context.
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
locale-agnostic conversion functions from floating point numbers to strings
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.
Definition utils.cpp:64
double toDouble(const std::string &s)
Converts a std::string to double using the classic C locale.
std::string toString(double d)
Convert a double to std::string using the classic C locale.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
The MoveIt interface to OMPL.
std::function< bool(const ompl::base::State *from, const ompl::base::State *to, const double t, ompl::base::State *state)> InterpolationFunction
This namespace includes the base class for MoveIt planners.
constraint_samplers::ConstraintSamplerManagerPtr constraint_sampler_manager_
ob::ConstrainedStateSpacePtr constrained_state_space_
OMPL constrained state space to handle path constraints.
moveit_msgs::msg::MoveItErrorCodes error_code
std::vector< robot_trajectory::RobotTrajectoryPtr > trajectory
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory