moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
move_action_capability.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
38
47
48namespace move_group
49{
50
51namespace
52{
53rclcpp::Logger getLogger()
54{
55 return moveit::getLogger("moveit.ros.move_group.move_action");
56}
57} // namespace
58
60 : MoveGroupCapability("move_action"), move_state_(IDLE), preempt_requested_{ false }
61{
62}
63
65{
66 // start the move action server
67 auto node = context_->moveit_cpp_->getNode();
68 execute_action_server_ = rclcpp_action::create_server<MGAction>(
69 node, MOVE_ACTION,
70 [](const rclcpp_action::GoalUUID& /*unused*/, const std::shared_ptr<const MGAction::Goal>& /*unused*/) {
71 RCLCPP_INFO(getLogger(), "MoveGroupMoveAction: Received request");
72 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
73 },
74 [this](const std::shared_ptr<MGActionGoal>& /*unused*/) {
75 RCLCPP_INFO(getLogger(), "MoveGroupMoveAction: Received request to cancel goal");
76 preemptMoveCallback();
77 return rclcpp_action::CancelResponse::ACCEPT;
78 },
79 [this](const std::shared_ptr<MGActionGoal>& goal) {
80 std::thread{ [this](const std::shared_ptr<move_group::MGActionGoal>& goal) { executeMoveCallback(goal); }, goal }
81 .detach();
82 });
83}
84
85void MoveGroupMoveAction::executeMoveCallback(const std::shared_ptr<MGActionGoal>& goal)
86{
87 goal_ = goal;
88 RCLCPP_INFO(getLogger(), "executing..");
89 setMoveState(PLANNING, goal_);
90 // before we start planning, ensure that we have the latest robot state received...
91 auto node = context_->moveit_cpp_->getNode();
92 context_->planning_scene_monitor_->waitForCurrentRobotState(node->get_clock()->now());
93 context_->planning_scene_monitor_->updateFrameTransforms();
94
95 auto action_res = std::make_shared<MGAction::Result>();
96 if (goal->get_goal()->planning_options.plan_only || !context_->allow_trajectory_execution_)
97 {
98 if (!goal->get_goal()->planning_options.plan_only)
99 {
100 RCLCPP_WARN(getLogger(), "This instance of MoveGroup is not allowed to execute trajectories "
101 "but the goal request has plan_only set to false. "
102 "Only a motion plan will be computed anyway.");
103 }
104 executeMoveCallbackPlanOnly(goal, action_res);
105 }
106 else
107 executeMoveCallbackPlanAndExecute(goal, action_res);
108
109 bool planned_trajectory_empty = trajectory_processing::isTrajectoryEmpty(action_res->planned_trajectory);
110 // @todo: Response messages
111 RCLCPP_INFO_STREAM(getLogger(), getActionResultString(action_res->error_code, planned_trajectory_empty,
112 goal->get_goal()->planning_options.plan_only));
113 if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
114 {
115 goal->succeed(action_res);
116 }
117 else if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
118 {
119 goal->canceled(action_res);
120 }
121 else
122 {
123 goal->abort(action_res);
124 }
125
126 setMoveState(IDLE, goal_);
127 preempt_requested_ = false;
128 goal_.reset();
129}
130
131void MoveGroupMoveAction::executeMoveCallbackPlanAndExecute(const std::shared_ptr<MGActionGoal>& goal,
132 std::shared_ptr<MGAction::Result>& action_res)
133{
134 RCLCPP_INFO(getLogger(), "Combined planning and execution request received for MoveGroup action. "
135 "Forwarding to planning and execution pipeline.");
136
137 if (moveit::core::isEmpty(goal->get_goal()->planning_options.planning_scene_diff))
138 {
139 planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_);
140 const moveit::core::RobotState& current_state = lscene->getCurrentState();
141
142 // check to see if the desired constraints are already met
143 for (std::size_t i = 0; i < goal->get_goal()->request.goal_constraints.size(); ++i)
144 {
145 if (lscene->isStateConstrained(
146 current_state, kinematic_constraints::mergeConstraints(goal->get_goal()->request.goal_constraints[i],
147 goal->get_goal()->request.path_constraints)))
148 {
149 RCLCPP_INFO(getLogger(), "Goal constraints are already satisfied. No need to plan or execute any motions");
150 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
151 return;
152 }
153 }
154 }
155
157
158 const moveit_msgs::msg::MotionPlanRequest& motion_plan_request =
159 moveit::core::isEmpty(goal->get_goal()->request.start_state) ? goal->get_goal()->request :
160 clearRequestStartState(goal->get_goal()->request);
161 const moveit_msgs::msg::PlanningScene& planning_scene_diff =
162 moveit::core::isEmpty(goal->get_goal()->planning_options.planning_scene_diff.robot_state) ?
163 goal->get_goal()->planning_options.planning_scene_diff :
164 clearSceneRobotState(goal->get_goal()->planning_options.planning_scene_diff);
165
166 opt.replan = goal->get_goal()->planning_options.replan;
167 opt.replan_attemps = goal->get_goal()->planning_options.replan_attempts;
168 opt.replan_delay = goal->get_goal()->planning_options.replan_delay;
169 opt.before_execution_callback_ = [this] { startMoveExecutionCallback(); };
170
171 opt.plan_callback = [this, &motion_plan_request](plan_execution::ExecutableMotionPlan& plan) {
172 return planUsingPlanningPipeline(motion_plan_request, plan);
173 };
174
176 if (preempt_requested_)
177 {
178 RCLCPP_INFO(getLogger(), "Preempt requested before the goal is planned and executed.");
179 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
180 return;
181 }
182
183 context_->plan_execution_->planAndExecute(plan, planning_scene_diff, opt);
184
185 convertToMsg(plan.plan_components, action_res->trajectory_start, action_res->planned_trajectory);
186 if (plan.executed_trajectory)
187 plan.executed_trajectory->getRobotTrajectoryMsg(action_res->executed_trajectory);
188 action_res->error_code = plan.error_code;
189}
190
191void MoveGroupMoveAction::executeMoveCallbackPlanOnly(const std::shared_ptr<MGActionGoal>& goal,
192 std::shared_ptr<MGAction::Result>& action_res)
193{
194 RCLCPP_INFO(getLogger(), "Planning request received for MoveGroup action. Forwarding to planning pipeline.");
195
196 // lock the scene so that it does not modify the world representation while diff() is called
197 planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_);
198 const planning_scene::PlanningSceneConstPtr& the_scene =
199 (moveit::core::isEmpty(goal->get_goal()->planning_options.planning_scene_diff)) ?
200 static_cast<const planning_scene::PlanningSceneConstPtr&>(lscene) :
201 lscene->diff(goal->get_goal()->planning_options.planning_scene_diff);
203
204 if (preempt_requested_)
205 {
206 RCLCPP_INFO(getLogger(), "Preempt requested before the goal is planned.");
207 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
208 return;
209 }
210
211 // Select planning_pipeline to handle request
212 const planning_pipeline::PlanningPipelinePtr planning_pipeline =
213 resolvePlanningPipeline(goal->get_goal()->request.pipeline_id);
215 {
216 action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
217 return;
218 }
219
220 try
221 {
222 if (!planning_pipeline->generatePlan(the_scene, goal->get_goal()->request, res, context_->debug_))
223 {
224 RCLCPP_ERROR(getLogger(), "Generating a plan with planning pipeline failed.");
225 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
226 }
227 }
228 catch (std::exception& ex)
229 {
230 RCLCPP_ERROR(getLogger(), "Planning pipeline threw an exception: %s", ex.what());
231 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
232 }
233
234 convertToMsg(res.trajectory, action_res->trajectory_start, action_res->planned_trajectory);
235 action_res->error_code = res.error_code;
236 action_res->planning_time = res.planning_time;
237}
238
239bool MoveGroupMoveAction::planUsingPlanningPipeline(const planning_interface::MotionPlanRequest& req,
241{
242 setMoveState(PLANNING, goal_);
243
244 bool solved = false;
246
247 // Select planning_pipeline to handle request
248 const planning_pipeline::PlanningPipelinePtr planning_pipeline = resolvePlanningPipeline(req.pipeline_id);
250 {
251 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
252 return solved;
253 }
254
255 planning_scene_monitor::LockedPlanningSceneRO lscene(plan.planning_scene_monitor);
256 try
257 {
258 solved = planning_pipeline->generatePlan(plan.planning_scene, req, res, context_->debug_);
259 }
260 catch (std::exception& ex)
261 {
262 RCLCPP_ERROR(getLogger(), "Planning pipeline threw an exception: %s", ex.what());
263 res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
264 }
265 if (res.trajectory)
266 {
267 plan.plan_components.resize(1);
268 plan.plan_components[0].trajectory = res.trajectory;
269 plan.plan_components[0].description = "plan";
270 }
272
273 return solved;
274}
275
276void MoveGroupMoveAction::startMoveExecutionCallback()
277{
278 setMoveState(MONITOR, goal_);
279}
280
281void MoveGroupMoveAction::startMoveLookCallback()
282{
283 setMoveState(LOOK, goal_);
284}
285
286void MoveGroupMoveAction::preemptMoveCallback()
287{
288 preempt_requested_ = true;
289 context_->plan_execution_->stop();
290}
291
292void MoveGroupMoveAction::setMoveState(MoveGroupState state, const std::shared_ptr<MGActionGoal>& goal)
293{
294 move_state_ = state;
295
296 if (goal)
297 {
298 auto move_feedback = std::make_shared<MGAction::Feedback>();
299 move_feedback->state = stateToStr(state);
300 goal->publish_feedback(move_feedback);
301 }
302}
303} // namespace move_group
304
305#include <pluginlib/class_list_macros.hpp>
306
PLUGINLIB_EXPORT_CLASS(cached_ik_kinematics_plugin::CachedIKKinematicsPlugin< kdl_kinematics_plugin::KDLKinematicsPlugin >, kinematics::KinematicsBase)
moveit_msgs::msg::PlanningScene clearSceneRobotState(const moveit_msgs::msg::PlanningScene &scene) const
planning_interface::MotionPlanRequest clearRequestStartState(const planning_interface::MotionPlanRequest &request) const
void convertToMsg(const std::vector< plan_execution::ExecutableTrajectory > &trajectory, moveit_msgs::msg::RobotState &first_state_msg, std::vector< moveit_msgs::msg::RobotTrajectory > &trajectory_msg) const
std::string getActionResultString(const moveit_msgs::msg::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only)
std::string stateToStr(MoveGroupState state) const
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition robot_state.h:90
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
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
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.
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)
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition logger.cpp:79
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
bool isTrajectoryEmpty(const moveit_msgs::msg::RobotTrajectory &trajectory)
Checks if a robot trajectory is empty.
A generic representation on what a computed motion plan looks like.
double replan_delay
The amount of time to wait in between replanning attempts (in seconds)
ExecutableMotionPlanComputationFn plan_callback
Callback for computing motion plans. This callback must always be specified.
std::function< void()> before_execution_callback_
bool replan
Flag indicating whether replanning is allowed.
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory