forked from moveit/moveit2
/
move_action_capability.cpp
285 lines (249 loc) · 11.8 KB
/
move_action_capability.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2012, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of Willow Garage nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
/* Author: Ioan Sucan */
#include "move_action_capability.h"
#include <moveit/planning_pipeline/planning_pipeline.h>
#include <moveit/plan_execution/plan_execution.h>
#include <moveit/plan_execution/plan_with_sensing.h>
#include <moveit/trajectory_processing/trajectory_tools.h>
#include <moveit/kinematic_constraints/utils.h>
#include <moveit/utils/message_checks.h>
#include <moveit/move_group/capability_names.h>
namespace move_group
{
static const rclcpp::Logger LOGGER =
rclcpp::get_logger("moveit_move_group_default_capabilities.move_action_capability");
MoveGroupMoveAction::MoveGroupMoveAction()
: MoveGroupCapability("MoveAction"), move_state_(IDLE), preempt_requested_{ false }
{
}
void MoveGroupMoveAction::initialize()
{
// start the move action server
using std::placeholders::_1;
using std::placeholders::_2;
auto node = context_->node_;
execute_action_server_ = rclcpp_action::create_server<MGAction>(
node->get_node_base_interface(), node->get_node_clock_interface(), node->get_node_logging_interface(),
node->get_node_waitables_interface(), MOVE_ACTION,
[](const rclcpp_action::GoalUUID& /*unused*/, std::shared_ptr<const MGAction::Goal> /*unused*/) {
RCLCPP_INFO(LOGGER, "Received request");
return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
},
[](const std::shared_ptr<MGActionGoal>& /*unused*/) {
RCLCPP_INFO(LOGGER, "Received request to cancel goal");
return rclcpp_action::CancelResponse::ACCEPT;
},
std::bind(&MoveGroupMoveAction::executeMoveCallback, this, _1));
}
void MoveGroupMoveAction::executeMoveCallback(std::shared_ptr<MGActionGoal> goal)
{
RCLCPP_INFO(LOGGER, "executing..");
setMoveState(PLANNING, goal);
// before we start planning, ensure that we have the latest robot state received...
context_->planning_scene_monitor_->waitForCurrentRobotState(rclcpp::Clock().now());
context_->planning_scene_monitor_->updateFrameTransforms();
auto action_res = std::make_shared<MGAction::Result>();
if (goal->get_goal()->planning_options.plan_only || !context_->allow_trajectory_execution_)
{
if (!goal->get_goal()->planning_options.plan_only)
RCLCPP_WARN(LOGGER, "This instance of MoveGroup is not allowed to execute trajectories "
"but the goal request has plan_only set to false. "
"Only a motion plan will be computed anyway.");
executeMoveCallbackPlanOnly(goal, action_res);
}
else
executeMoveCallbackPlanAndExecute(goal, action_res);
bool planned_trajectory_empty = trajectory_processing::isTrajectoryEmpty(action_res->planned_trajectory);
// @todo: Response messages
std::string response = getActionResultString(action_res->error_code, planned_trajectory_empty,
goal->get_goal()->planning_options.plan_only);
auto fb = std::make_shared<MGAction::Feedback>();
fb->state = response;
if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
{
goal->succeed(action_res);
goal->publish_feedback(fb);
}
else
{
if (action_res->error_code.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
{
goal->canceled(action_res);
}
else
{
goal->abort(action_res);
goal->publish_feedback(fb);
}
}
setMoveState(IDLE, goal);
preempt_requested_ = false;
}
void MoveGroupMoveAction::executeMoveCallbackPlanAndExecute(const std::shared_ptr<MGActionGoal>& goal,
std::shared_ptr<MGAction::Result>& action_res)
{
RCLCPP_INFO(LOGGER, "Combined planning and execution request received for MoveGroup action. "
"Forwarding to planning and execution pipeline.");
if (moveit::core::isEmpty(goal->get_goal()->planning_options.planning_scene_diff))
{
planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_);
const moveit::core::RobotState& current_state = lscene->getCurrentState();
// check to see if the desired constraints are already met
for (std::size_t i = 0; i < goal->get_goal()->request.goal_constraints.size(); ++i)
if (lscene->isStateConstrained(
current_state, kinematic_constraints::mergeConstraints(goal->get_goal()->request.goal_constraints[i],
goal->get_goal()->request.path_constraints)))
{
RCLCPP_INFO(LOGGER, "Goal constraints are already satisfied. No need to plan or execute any motions");
action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
return;
}
}
plan_execution::PlanExecution::Options opt;
const moveit_msgs::msg::MotionPlanRequest& motion_plan_request =
moveit::core::isEmpty(goal->get_goal()->request.start_state) ? goal->get_goal()->request :
clearRequestStartState(goal->get_goal()->request);
const moveit_msgs::msg::PlanningScene& planning_scene_diff =
moveit::core::isEmpty(goal->get_goal()->planning_options.planning_scene_diff.robot_state) ?
goal->get_goal()->planning_options.planning_scene_diff :
clearSceneRobotState(goal->get_goal()->planning_options.planning_scene_diff);
opt.replan_ = goal->get_goal()->planning_options.replan;
opt.replan_attempts_ = goal->get_goal()->planning_options.replan_attempts;
opt.replan_delay_ = goal->get_goal()->planning_options.replan_delay;
opt.before_execution_callback_ = boost::bind(&MoveGroupMoveAction::startMoveExecutionCallback, this);
opt.plan_callback_ = boost::bind(&MoveGroupMoveAction::planUsingPlanningPipeline, this,
boost::cref(motion_plan_request), boost::placeholders::_1);
if (goal->get_goal()->planning_options.look_around && context_->plan_with_sensing_)
{
opt.plan_callback_ = boost::bind(&plan_execution::PlanWithSensing::computePlan, context_->plan_with_sensing_.get(),
boost::placeholders::_1, opt.plan_callback_,
goal->get_goal()->planning_options.look_around_attempts,
goal->get_goal()->planning_options.max_safe_execution_cost);
context_->plan_with_sensing_->setBeforeLookCallback(boost::bind(&MoveGroupMoveAction::startMoveLookCallback, this));
}
plan_execution::ExecutableMotionPlan plan;
if (preempt_requested_)
{
RCLCPP_INFO(LOGGER, "Preempt requested before the goal is planned and executed.");
action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
return;
}
context_->plan_execution_->planAndExecute(plan, planning_scene_diff, opt);
convertToMsg(plan.plan_components_, action_res->trajectory_start, action_res->planned_trajectory);
if (plan.executed_trajectory_)
plan.executed_trajectory_->getRobotTrajectoryMsg(action_res->executed_trajectory);
action_res->error_code = plan.error_code_;
}
void MoveGroupMoveAction::executeMoveCallbackPlanOnly(const std::shared_ptr<MGActionGoal>& goal,
std::shared_ptr<MGAction::Result>& action_res)
{
RCLCPP_INFO(LOGGER, "Planning request received for MoveGroup action. Forwarding to planning pipeline.");
// lock the scene so that it does not modify the world representation while diff() is called
planning_scene_monitor::LockedPlanningSceneRO lscene(context_->planning_scene_monitor_);
const planning_scene::PlanningSceneConstPtr& the_scene =
(moveit::core::isEmpty(goal->get_goal()->planning_options.planning_scene_diff)) ?
static_cast<const planning_scene::PlanningSceneConstPtr&>(lscene) :
lscene->diff(goal->get_goal()->planning_options.planning_scene_diff);
planning_interface::MotionPlanResponse res;
if (preempt_requested_)
{
RCLCPP_INFO(LOGGER, "Preempt requested before the goal is planned.");
action_res->error_code.val = moveit_msgs::msg::MoveItErrorCodes::PREEMPTED;
return;
}
try
{
context_->planning_pipeline_->generatePlan(the_scene, goal->get_goal()->request, res);
}
catch (std::exception& ex)
{
RCLCPP_ERROR(LOGGER, "Planning pipeline threw an exception: %s", ex.what());
res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
}
convertToMsg(res.trajectory_, action_res->trajectory_start, action_res->planned_trajectory);
action_res->error_code = res.error_code_;
action_res->planning_time = res.planning_time_;
}
bool MoveGroupMoveAction::planUsingPlanningPipeline(const planning_interface::MotionPlanRequest& req,
plan_execution::ExecutableMotionPlan& plan)
{
setMoveState(PLANNING, nullptr);
planning_scene_monitor::LockedPlanningSceneRO lscene(plan.planning_scene_monitor_);
bool solved = false;
planning_interface::MotionPlanResponse res;
try
{
solved = context_->planning_pipeline_->generatePlan(plan.planning_scene_, req, res);
}
catch (std::exception& ex)
{
RCLCPP_ERROR(LOGGER, "Planning pipeline threw an exception: %s", ex.what());
res.error_code_.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
}
if (res.trajectory_)
{
plan.plan_components_.resize(1);
plan.plan_components_[0].trajectory_ = res.trajectory_;
plan.plan_components_[0].description_ = "plan";
}
plan.error_code_ = res.error_code_;
return solved;
}
void MoveGroupMoveAction::startMoveExecutionCallback()
{
setMoveState(MONITOR, nullptr);
}
void MoveGroupMoveAction::startMoveLookCallback()
{
setMoveState(LOOK, nullptr);
}
void MoveGroupMoveAction::preemptMoveCallback()
{
preempt_requested_ = true;
context_->plan_execution_->stop();
}
void MoveGroupMoveAction::setMoveState(MoveGroupState state, const std::shared_ptr<MGActionGoal>& goal)
{
move_state_ = state;
if (goal)
{
auto move_feedback = std::make_shared<MGAction::Feedback>();
move_feedback->state = stateToStr(state);
goal->publish_feedback(move_feedback);
}
}
} // namespace move_group
#include <pluginlib/class_list_macros.hpp>
PLUGINLIB_EXPORT_CLASS(move_group::MoveGroupMoveAction, move_group::MoveGroupCapability)