66 : MoveGroupCapability(
"SequenceAction")
67 , move_feedback_(std::make_shared<moveit_msgs::
action::MoveGroupSequence::Feedback>())
74 RCLCPP_INFO_STREAM(
getLogger(),
"initialize move group sequence action");
75 action_callback_group_ =
76 context_->moveit_cpp_->getNode()->create_callback_group(rclcpp::CallbackGroupType::Reentrant);
77 move_action_server_ = rclcpp_action::create_server<moveit_msgs::action::MoveGroupSequence>(
78 context_->moveit_cpp_->getNode(),
"sequence_move_group",
79 [](
const rclcpp_action::GoalUUID& ,
80 const std::shared_ptr<const moveit_msgs::action::MoveGroupSequence::Goal>& ) {
81 RCLCPP_DEBUG(getLogger(),
"Received action goal");
82 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
84 [
this](
const std::shared_ptr<MoveGroupSequenceGoalHandle>& ) {
85 RCLCPP_DEBUG(getLogger(),
"Canceling action goal");
86 preemptMoveCallback();
87 return rclcpp_action::CancelResponse::ACCEPT;
89 [
this](
const std::shared_ptr<MoveGroupSequenceGoalHandle>& goal_handle) {
90 RCLCPP_DEBUG(getLogger(),
"Accepting new action goal");
91 executeSequenceCallback(goal_handle);
93 rcl_action_server_get_default_options(), action_callback_group_);
95 command_list_manager_ = std::make_unique<pilz_industrial_motion_planner::CommandListManager>(
96 context_->moveit_cpp_->getNode(),
context_->planning_scene_monitor_->getRobotModel());
99 void MoveGroupSequenceAction::executeSequenceCallback(
const std::shared_ptr<MoveGroupSequenceGoalHandle>& goal_handle)
102 goal_handle_ = goal_handle;
103 const auto goal = goal_handle->get_goal();
108 if (goal->request.items.empty())
110 RCLCPP_WARN(
getLogger(),
"Received empty request. That's ok but maybe not what you intended.");
112 const auto action_res = std::make_shared<moveit_msgs::action::MoveGroupSequence::Result>();
113 action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
114 goal_handle->succeed(action_res);
120 auto node =
context_->moveit_cpp_->getNode();
121 context_->planning_scene_monitor_->waitForCurrentRobotState(node->get_clock()->now());
122 context_->planning_scene_monitor_->updateFrameTransforms();
124 const auto action_res = std::make_shared<moveit_msgs::action::MoveGroupSequence::Result>();
125 if (goal->planning_options.plan_only || !
context_->allow_trajectory_execution_)
127 if (!goal->planning_options.plan_only)
129 RCLCPP_WARN(
getLogger(),
"Only plan will be calculated, although plan_only == false.");
131 executeMoveCallbackPlanOnly(goal, action_res);
135 executeSequenceCallbackPlanAndExecute(goal, action_res);
138 switch (action_res->response.error_code.val)
140 case moveit_msgs::msg::MoveItErrorCodes::SUCCESS:
141 goal_handle->succeed(action_res);
143 case moveit_msgs::msg::MoveItErrorCodes::PREEMPTED:
144 goal_handle->canceled(action_res);
147 goal_handle->abort(action_res);
152 goal_handle_.reset();
155 void MoveGroupSequenceAction::executeSequenceCallbackPlanAndExecute(
156 const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
157 const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& action_res)
159 RCLCPP_INFO(
getLogger(),
"Combined planning and execution request received for MoveGroupSequenceAction.");
162 const moveit_msgs::msg::PlanningScene& planning_scene_diff =
164 goal->planning_options.planning_scene_diff :
167 opt.
replan = goal->planning_options.replan;
173 return planUsingSequenceManager(request,
plan);
177 context_->plan_execution_->planAndExecute(
plan, planning_scene_diff, opt);
179 StartStatesMsg start_states_msg;
180 convertToMsg(
plan.plan_components, start_states_msg, action_res->response.planned_trajectories);
183 action_res->response.sequence_start = start_states_msg.at(0);
185 catch (std::out_of_range&)
187 RCLCPP_WARN(
getLogger(),
"Can not determine start state from empty sequence.");
192 void MoveGroupSequenceAction::convertToMsg(
const ExecutableTrajs& trajs, StartStatesMsg& start_states_msg,
193 PlannedTrajMsgs& planned_trajs_msgs)
195 start_states_msg.resize(trajs.size());
196 planned_trajs_msgs.resize(trajs.size());
197 for (
size_t i = 0; i < trajs.size(); ++i)
200 trajs.at(i).trajectory->getRobotTrajectoryMsg(planned_trajs_msgs.at(i));
204 void MoveGroupSequenceAction::executeMoveCallbackPlanOnly(
205 const moveit_msgs::action::MoveGroupSequence::Goal::ConstSharedPtr& goal,
206 const moveit_msgs::action::MoveGroupSequence::Result::SharedPtr& action_res)
208 RCLCPP_INFO(
getLogger(),
"Planning request received for MoveGroupSequenceAction action.");
214 const planning_scene::PlanningSceneConstPtr& the_scene =
216 static_cast<const planning_scene::PlanningSceneConstPtr&
>(lscene) :
217 lscene->diff(goal->planning_options.planning_scene_diff);
219 rclcpp::Time planning_start =
context_->moveit_cpp_->getNode()->now();
229 RCLCPP_ERROR_STREAM(
getLogger(),
"Could not load planning pipeline " << goal->request.items[0].req.pipeline_id);
230 action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
234 traj_vec = command_list_manager_->solve(the_scene,
planning_pipeline, goal->request);
236 catch (
const MoveItErrorCodeException& ex)
238 RCLCPP_ERROR_STREAM(
getLogger(),
"> Planning pipeline threw an exception (error code: " << ex.getErrorCode()
239 <<
"): " << ex.what());
240 action_res->response.error_code.val = ex.getErrorCode();
244 catch (
const std::exception& ex)
246 RCLCPP_ERROR(
getLogger(),
"Planning pipeline threw an exception: %s", ex.what());
247 action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
252 StartStatesMsg start_states_msg;
253 start_states_msg.resize(traj_vec.size());
254 action_res->response.planned_trajectories.resize(traj_vec.size());
255 for (RobotTrajCont::size_type i = 0; i < traj_vec.size(); ++i)
258 action_res->response.planned_trajectories.at(i));
262 action_res->response.sequence_start = start_states_msg.at(0);
264 catch (std::out_of_range&)
266 RCLCPP_WARN(
getLogger(),
"Can not determine start state from empty sequence.");
269 action_res->response.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
270 action_res->response.planning_time = (
context_->moveit_cpp_->getNode()->now() - planning_start).seconds();
273 bool MoveGroupSequenceAction::planUsingSequenceManager(
const moveit_msgs::msg::MotionSequenceRequest& req,
288 RCLCPP_ERROR_STREAM(
getLogger(),
"Could not load planning pipeline " << req.items[0].req.pipeline_id);
294 catch (
const MoveItErrorCodeException& ex)
296 RCLCPP_ERROR_STREAM(
getLogger(),
"Planning pipeline threw an exception (error code: " << ex.getErrorCode()
297 <<
"): " << ex.what());
302 catch (
const std::exception& ex)
304 RCLCPP_ERROR_STREAM(
getLogger(),
"Planning pipeline threw an exception: " << ex.what());
305 plan.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::FAILURE;
310 if (!traj_vec.empty())
312 plan.plan_components.resize(traj_vec.size());
313 for (
size_t i = 0; i < traj_vec.size(); ++i)
316 plan.plan_components.at(i).description =
"plan";
319 plan.
error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
323 void MoveGroupSequenceAction::startMoveExecutionCallback()
328 void MoveGroupSequenceAction::preemptMoveCallback()
337 goal_handle_->publish_feedback(move_feedback_);
342 #include <pluginlib/class_list_macros.hpp>
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
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
MoveGroupContextPtr context_
std::string stateToStr(MoveGroupState state) const
planning_pipeline::PlanningPipelinePtr resolvePlanningPipeline(const std::string &pipeline_id) const
Provide action to handle multiple trajectories and execute the result in the form of a MoveGroup capa...
void initialize() override
MoveGroupSequenceAction()
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
rclcpp::Logger getLogger()
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
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.
std::vector< robot_trajectory::RobotTrajectoryPtr > RobotTrajCont
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)
unsigned int replan_attemps
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.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory