moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
plan_execution.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
43#include <boost/algorithm/string/join.hpp>
44#include <rclcpp/logger.hpp>
45#include <rclcpp/logging.hpp>
46#include <rclcpp/node.hpp>
47#include <rclcpp/parameter_value.hpp>
48#include <rclcpp/rate.hpp>
49#include <rclcpp/utilities.hpp>
51
52// #include <dynamic_reconfigure/server.h>
53// #include <moveit_ros_planning/PlanExecutionDynamicReconfigureConfig.h>
54
55namespace plan_execution
56{
57
58// class PlanExecution::DynamicReconfigureImpl
59// {
60// public:
61// DynamicReconfigureImpl(PlanExecution* owner)
62// : owner_(owner) //, dynamic_reconfigure_server_(ros::NodeHandle("~/plan_execution"))
63// {
64// // dynamic_reconfigure_server_.setCallback(
65// // [this](const auto& config, uint32_t level) { dynamicReconfigureCallback(config, level); });
66// }
67//
68// private:
69// // void dynamicReconfigureCallback(const PlanExecutionDynamicReconfigureConfig& config, uint32_t level)
70// // {
71// // owner_->setMaxReplanAttempts(config.max_replan_attempts);
72// // owner_->setTrajectoryStateRecordingFrequency(config.record_trajectory_state_frequency);
73// // }
74//
75// PlanExecution* owner_;
76// // dynamic_reconfigure::Server<PlanExecutionDynamicReconfigureConfig> dynamic_reconfigure_server_;
77// };
78} // namespace plan_execution
79
81 const rclcpp::Node::SharedPtr& node, const planning_scene_monitor::PlanningSceneMonitorPtr& planning_scene_monitor,
82 const trajectory_execution_manager::TrajectoryExecutionManagerPtr& trajectory_execution)
83 : node_(node)
84 , planning_scene_monitor_(planning_scene_monitor)
85 , trajectory_execution_manager_(trajectory_execution)
86 , logger_(moveit::getLogger("moveit.ros.add_time_optimal_parameterization"))
87{
88 if (!trajectory_execution_manager_)
89 {
90 trajectory_execution_manager_ = std::make_shared<trajectory_execution_manager::TrajectoryExecutionManager>(
91 node_, planning_scene_monitor_->getRobotModel(), planning_scene_monitor_->getStateMonitor());
92 }
93
94 default_max_replan_attempts_ = 5;
95
96 new_scene_update_ = false;
97
98 // we want to be notified when new information is available
99 planning_scene_monitor_->addUpdateCallback(
101 planningSceneUpdatedCallback(update_type);
102 });
103
104 // start the dynamic-reconfigure server
105 // reconfigure_impl_ = new DynamicReconfigureImpl(this);
106}
107
109{
110 // delete reconfigure_impl_;
111}
112
114{
115 preempt_.request();
116}
117
119{
120 plan.planning_scene_monitor = planning_scene_monitor_;
121 plan.planning_scene = planning_scene_monitor_->getPlanningScene();
122 planAndExecuteHelper(plan, opt);
123}
124
126 const moveit_msgs::msg::PlanningScene& scene_diff,
127 const Options& opt)
128{
129 if (moveit::core::isEmpty(scene_diff))
130 {
131 planAndExecute(plan, opt);
132 }
133 else
134 {
135 plan.planning_scene_monitor = planning_scene_monitor_;
136 {
137 planning_scene_monitor::LockedPlanningSceneRO lscene(planning_scene_monitor_); // lock the scene so that it does
138 // not modify the world
139 // representation while diff() is
140 // called
141 plan.planning_scene = lscene->diff(scene_diff);
142 }
143 planAndExecuteHelper(plan, opt);
144 }
145}
146
147void plan_execution::PlanExecution::planAndExecuteHelper(ExecutableMotionPlan& plan, const Options& opt)
148{
149 // perform initial configuration steps & various checks
150 preempt_.checkAndClear(); // clear any previous preempt_ request
151
152 bool preempt_requested = false;
153
154 // run the actual motion plan & execution
155 unsigned int max_replan_attempts =
156 opt.replan ? (opt.replan_attemps > 0 ? opt.replan_attemps : default_max_replan_attempts_) : 1;
157 unsigned int replan_attempts = 0;
158 bool previously_solved = false;
159
160 // run a planning loop for at most the maximum replanning attempts;
161 // re-planning is executed only in case of known types of failures (e.g., environment changed)
162 do
163 {
164 replan_attempts++;
165 RCLCPP_INFO(logger_, "Planning attempt %u of at most %u", replan_attempts, max_replan_attempts);
166
167 if (opt.before_plan_callback_)
168 opt.before_plan_callback_();
169
170 new_scene_update_ = false; // we clear any scene updates to be evaluated because we are about to compute a new
171 // plan, which should consider most recent updates already
172
173 // if we never had a solved plan, or there is no specified way of fixing plans, just call the planner; otherwise,
174 // try to repair the plan we previously had;
175 bool solved =
176 (!previously_solved || !opt.repair_plan_callback_) ?
177 opt.plan_callback(plan) :
178 opt.repair_plan_callback_(plan, trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex());
179
180 preempt_requested = preempt_.checkAndClear();
181 if (preempt_requested)
182 break;
183
184 // if planning fails in a manner that is not recoverable, we exit the loop,
185 // otherwise, we attempt to continue, if replanning attempts are left
186 if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED ||
187 plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN ||
188 plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA)
189 {
190 if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA &&
191 opt.replan_delay > 0.0)
192 {
193 auto replan_delay_seconds = std::chrono::duration<double>(opt.replan_delay);
194 rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(replan_delay_seconds));
195 }
196 continue;
197 }
198
199 // abort if no plan was found
200 if (solved)
201 {
202 previously_solved = true;
203 }
204 else
205 {
206 break;
207 }
208
209 if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
210 {
211 if (opt.before_execution_callback_)
212 opt.before_execution_callback_();
213
214 preempt_requested = preempt_.checkAndClear();
215 if (preempt_requested)
216 break;
217
218 // execute the trajectory, and monitor its execution
219 plan.error_code = executeAndMonitor(plan, false);
220 }
221
222 if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
223 preempt_requested = true;
224
225 // if execution succeeded or failed in a manner that we do not consider recoverable, we exit the loop (with failure)
226 if (plan.error_code.val != moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
227 {
228 break;
229 }
230 else
231 {
232 // otherwise, we wait (if needed)
233 if (opt.replan_delay > 0.0)
234 {
235 RCLCPP_INFO(logger_, "Waiting for a %lf seconds before attempting a new plan ...", opt.replan_delay);
236 auto replan_delay_seconds = std::chrono::duration<double>(opt.replan_delay);
237 rclcpp::sleep_for(std::chrono::duration_cast<std::chrono::nanoseconds>(replan_delay_seconds));
238 RCLCPP_INFO(logger_, "Done waiting");
239 }
240 }
241
242 preempt_requested = preempt_.checkAndClear();
243 if (preempt_requested)
244 break;
245
246 } while (replan_attempts < max_replan_attempts);
247
248 if (preempt_requested)
249 {
250 RCLCPP_DEBUG(logger_, "PlanExecution was preempted");
251 plan.error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
252 }
253
254 if (opt.done_callback_)
255 opt.done_callback_();
256
257 if (plan.error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
258 {
259 RCLCPP_DEBUG(logger_, "PlanExecution finished successfully.");
260 }
261 else
262 {
263 RCLCPP_DEBUG(logger_, "PlanExecution terminating with error code %d - '%s'", plan.error_code.val,
265 }
266}
267
268bool plan_execution::PlanExecution::isRemainingPathValid(const ExecutableMotionPlan& plan,
269 const std::pair<int, int>& path_segment)
270{
271 if (path_segment.first >= 0 &&
272 plan.plan_components[path_segment.first].trajectory_monitoring) // If path_segment.second <= 0, the function
273 // will fallback to check the entire trajectory
274 {
275 planning_scene_monitor::LockedPlanningSceneRO lscene(plan.planning_scene_monitor); // lock the scene so that it
276 // does not modify the world
277 // representation while
278 // isStateValid() is called
279 const robot_trajectory::RobotTrajectory& t = *plan.plan_components[path_segment.first].trajectory;
281 plan.plan_components[path_segment.first].allowed_collision_matrix.get();
282 std::size_t wpc = t.getWayPointCount();
284 req.group_name = t.getGroupName();
285 req.pad_environment_collisions = false;
286 for (std::size_t i = std::max(path_segment.second - 1, 0); i < wpc; ++i)
287 {
289 if (acm)
290 {
291 plan.planning_scene->checkCollision(req, res, t.getWayPoint(i), *acm);
292 }
293 else
294 {
295 plan.planning_scene->checkCollision(req, res, t.getWayPoint(i));
296 }
297
298 if (res.collision || !plan.planning_scene->isStateFeasible(t.getWayPoint(i), false))
299 {
300 // Dave's debacle
301 RCLCPP_INFO(logger_, "Trajectory component '%s' is invalid",
302 plan.plan_components[path_segment.first].description.c_str());
303
304 // call the same functions again, in verbose mode, to show what issues have been detected
305 plan.planning_scene->isStateFeasible(t.getWayPoint(i), true);
306 req.verbose = true;
307 res.clear();
308 if (acm)
309 {
310 plan.planning_scene->checkCollision(req, res, t.getWayPoint(i), *acm);
311 }
312 else
313 {
314 plan.planning_scene->checkCollision(req, res, t.getWayPoint(i));
315 }
316 return false;
317 }
318 }
319 }
320 return true;
321}
322
324 bool reset_preempted)
325{
326 if (reset_preempted)
327 preempt_.checkAndClear();
328
329 if (!plan.planning_scene_monitor)
330 plan.planning_scene_monitor = planning_scene_monitor_;
331 if (!plan.planning_scene)
332 plan.planning_scene = planning_scene_monitor_->getPlanningScene();
333
334 moveit_msgs::msg::MoveItErrorCodes result;
335
336 // try to execute the trajectory
337 execution_complete_ = true;
338
339 if (!trajectory_execution_manager_)
340 {
341 RCLCPP_ERROR(logger_, "No trajectory execution manager");
342 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
343 return result;
344 }
345
346 if (plan.plan_components.empty())
347 {
348 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
349 return result;
350 }
351
352 execution_complete_ = false;
353
354 // push the trajectories we have slated for execution to the trajectory execution manager
355 int prev = -1;
356 for (size_t component_idx = 0; component_idx < plan.plan_components.size(); ++component_idx)
357 {
358 // \todo should this be in trajectory_execution ? Maybe. Then that will have to use kinematic_trajectory too;
359 // splitting trajectories for controllers becomes interesting: tied to groups instead of joints. this could cause
360 // some problems
361 // in the meantime we do a hack:
362
363 bool unwound = false;
364 for (int prev_component = component_idx - 1; prev_component >= 0; --prev_component)
365 {
366 // Search backward for a previous component having the same group.
367 // If the group is the same, unwind this component based on the last waypoint of the previous one.
368 if (plan.plan_components.at(prev_component).trajectory &&
369 plan.plan_components.at(prev_component).trajectory->getGroup() ==
370 plan.plan_components.at(prev_component).trajectory->getGroup() &&
371 !plan.plan_components.at(prev_component).trajectory->empty())
372 {
373 plan.plan_components.at(component_idx)
374 .trajectory->unwind(plan.plan_components.at(prev_component).trajectory->getLastWayPoint());
375 unwound = true;
376 // Break so each component is only unwound once
377 break;
378 }
379 }
380
381 if (!unwound)
382 {
383 // unwind the path to execute based on the current state of the system
384 if (prev < 0)
385 {
386 plan.plan_components[component_idx].trajectory->unwind(
387 plan.planning_scene_monitor && plan.planning_scene_monitor->getStateMonitor() ?
388 *plan.planning_scene_monitor->getStateMonitor()->getCurrentState() :
389 plan.planning_scene->getCurrentState());
390 }
391 else
392 {
393 plan.plan_components[component_idx].trajectory->unwind(plan.plan_components[prev].trajectory->getLastWayPoint());
394 }
395 }
396
397 if (plan.plan_components[component_idx].trajectory && !plan.plan_components[component_idx].trajectory->empty())
398 prev = component_idx;
399
400 // convert to message, pass along
401 moveit_msgs::msg::RobotTrajectory msg;
402 plan.plan_components[component_idx].trajectory->getRobotTrajectoryMsg(msg);
403 if (!trajectory_execution_manager_->push(msg, plan.plan_components[component_idx].controller_name))
404 {
405 trajectory_execution_manager_->clear();
406 RCLCPP_ERROR(logger_, "Apparently trajectory initialization failed");
407 execution_complete_ = true;
408 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
409 return result;
410 }
411 }
412
413 if (!trajectory_monitor_ && planning_scene_monitor_->getStateMonitor())
414 {
415 // Pass current value of reconfigurable parameter plan_execution/record_trajectory_state_frequency
416 double sampling_frequency = 0.0;
417 node_->get_parameter_or("plan_execution.record_trajectory_state_frequency", sampling_frequency, 0.0);
418 trajectory_monitor_ = std::make_shared<planning_scene_monitor::TrajectoryMonitor>(
419 planning_scene_monitor_->getStateMonitor(), sampling_frequency);
420 }
421
422 // start recording trajectory states
423 if (trajectory_monitor_)
424 trajectory_monitor_->startTrajectoryMonitor();
425
426 // start a trajectory execution thread
427 trajectory_execution_manager_->execute(
428 [this](const moveit_controller_manager::ExecutionStatus& status) { doneWithTrajectoryExecution(status); },
429 [this, &plan](std::size_t index) { successfulTrajectorySegmentExecution(plan, index); });
430 // wait for path to be done, while checking that the path does not become invalid
431 rclcpp::WallRate r(100);
432 path_became_invalid_ = false;
433 bool preempt_requested = false;
434
435 while (rclcpp::ok() && !execution_complete_ && !path_became_invalid_)
436 {
437 r.sleep();
438 // check the path if there was an environment update in the meantime
439 if (new_scene_update_)
440 {
441 new_scene_update_ = false;
442 std::pair<int, int> current_index = trajectory_execution_manager_->getCurrentExpectedTrajectoryIndex();
443 if (!isRemainingPathValid(plan, current_index))
444 {
445 RCLCPP_INFO(logger_, "Trajectory component '%s' is invalid after scene update",
446 plan.plan_components[current_index.first].description.c_str());
447 path_became_invalid_ = true;
448 break;
449 }
450 }
451
452 preempt_requested = preempt_.checkAndClear();
453 if (preempt_requested)
454 break;
455 }
456
457 // stop execution if needed
458 if (preempt_requested)
459 {
460 RCLCPP_INFO(logger_, "Stopping execution due to preempt request");
461 trajectory_execution_manager_->stopExecution();
462 }
463 else if (path_became_invalid_)
464 {
465 RCLCPP_INFO(logger_, "Stopping execution because the path to execute became invalid"
466 "(probably the environment changed)");
467 trajectory_execution_manager_->stopExecution();
468 }
469 else if (!execution_complete_)
470 {
471 RCLCPP_WARN(logger_, "Stopping execution due to unknown reason."
472 "Possibly the node is about to shut down.");
473 trajectory_execution_manager_->stopExecution();
474 }
475
476 // stop recording trajectory states
477 if (trajectory_monitor_)
478 {
479 trajectory_monitor_->stopTrajectoryMonitor();
480 plan.executed_trajectory =
481 std::make_shared<robot_trajectory::RobotTrajectory>(planning_scene_monitor_->getRobotModel(), "");
482 trajectory_monitor_->swapTrajectory(*plan.executed_trajectory);
483 }
484
485 // decide return value
486 if (path_became_invalid_)
487 {
488 result.val = moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE;
489 }
490 else
491 {
492 if (preempt_requested)
493 {
494 result.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
495 }
496 else
497 {
498 if (trajectory_execution_manager_->getLastExecutionStatus() ==
500 {
501 result.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
502 }
503 else if (trajectory_execution_manager_->getLastExecutionStatus() ==
505 {
506 result.val = moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT;
507 }
508 else
509 {
510 result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
511 }
512 }
513 }
514 return result;
515}
516
517void plan_execution::PlanExecution::planningSceneUpdatedCallback(
519{
522 new_scene_update_ = true;
523}
524
525void plan_execution::PlanExecution::doneWithTrajectoryExecution(
527{
528 execution_complete_ = true;
529}
530
531void plan_execution::PlanExecution::successfulTrajectorySegmentExecution(const ExecutableMotionPlan& plan,
532 std::size_t index)
533{
534 if (plan.plan_components.empty())
535 {
536 RCLCPP_WARN(logger_, "Length of provided motion plan is zero.");
537 return;
538 }
539
540 // if any side-effects are associated to the trajectory part that just completed, execute them
541 RCLCPP_DEBUG(logger_, "Completed '%s'", plan.plan_components[index].description.c_str());
542 if (plan.plan_components[index].effect_on_success)
543 {
544 if (!plan.plan_components[index].effect_on_success(&plan))
545 {
546 // execution of side-effect failed
547 RCLCPP_ERROR(logger_, "Execution of path-completion side-effect failed. Preempting.");
548 preempt_.request();
549 return;
550 }
551 }
552
553 // if there is a next trajectory, check it for validity, before we start execution
554 ++index;
555 if (index < plan.plan_components.size() && plan.plan_components[index].trajectory &&
556 !plan.plan_components[index].trajectory->empty())
557 {
558 std::pair<int, int> next_index(static_cast<int>(index), 0);
559 if (!isRemainingPathValid(plan, next_index))
560 {
561 RCLCPP_INFO(logger_, "Upcoming trajectory component '%s' is invalid",
562 plan.plan_components[next_index.first].description.c_str());
563 path_became_invalid_ = true;
564 }
565 }
566}
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void planAndExecute(ExecutableMotionPlan &plan, const Options &opt)
PlanExecution(const rclcpp::Node::SharedPtr &node, const planning_scene_monitor::PlanningSceneMonitorPtr &planning_scene_monitor, const trajectory_execution_manager::TrajectoryExecutionManagerPtr &trajectory_execution)
moveit_msgs::msg::MoveItErrorCodes executeAndMonitor(ExecutableMotionPlan &plan, bool reset_preempted=true)
Execute and monitor a previously created plan.
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
@ UPDATE_GEOMETRY
The geometry of the scene was updated. This includes receiving new octomaps, collision objects,...
@ UPDATE_TRANSFORMS
The maintained set of fixed transforms in the monitored scene was updated.
Maintain a sequence of waypoints and the time durations between these waypoints.
const std::string & getGroupName() const
const moveit::core::RobotState & getWayPoint(std::size_t index) const
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
std::string errorCodeToString(const MoveItErrorCode &error_code)
Convenience function to translated error message into string.
planning_interface::MotionPlanResponse plan(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
Main namespace for MoveIt.
Definition exceptions.h:43
This namespace includes functionality specific to the execution and monitoring of motion plans.
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)....
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool pad_environment_collisions
If true, use padded collision environment.
Representation of a collision checking result.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW void clear()
Clear a previously stored result.
bool collision
True if collision was found, false otherwise.
A generic representation on what a computed motion plan looks like.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory