41#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
63 moveit_msgs::msg::RobotState& first_state_msg,
64 std::vector<moveit_msgs::msg::RobotTrajectory>& trajectory_msg)
const
66 if (!trajectory.empty())
69 trajectory_msg.resize(trajectory.size());
70 for (std::size_t i = 0; i < trajectory.size(); ++i)
72 if (trajectory[i].trajectory)
74 if (first && !trajectory[i].trajectory->empty())
79 trajectory[i].trajectory->getRobotTrajectoryMsg(trajectory_msg[i]);
86 moveit_msgs::msg::RobotState& first_state_msg,
87 moveit_msgs::msg::RobotTrajectory& trajectory_msg)
const
89 if (trajectory && !trajectory->empty())
92 trajectory->getRobotTrajectoryMsg(trajectory_msg);
97 moveit_msgs::msg::RobotState& first_state_msg,
98 moveit_msgs::msg::RobotTrajectory& trajectory_msg)
const
100 if (trajectory.size() > 1)
102 RCLCPP_ERROR_STREAM(getLogger(),
103 "Internal logic error: trajectory component ignored. !!! THIS IS A SERIOUS ERROR !!!");
105 if (!trajectory.empty())
107 convertToMsg(trajectory[0].trajectory, first_state_msg, trajectory_msg);
115 r.start_state = moveit_msgs::msg::RobotState();
116 r.start_state.is_diff =
true;
117 RCLCPP_WARN(getLogger(),
118 "Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
119 "start state in the motion planning request");
123moveit_msgs::msg::PlanningScene
126 moveit_msgs::msg::PlanningScene r = scene;
127 r.robot_state = moveit_msgs::msg::RobotState();
128 r.robot_state.is_diff =
true;
129 RCLCPP_WARN(getLogger(),
130 "Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
131 "difference in the planning scene diff");
136 bool planned_trajectory_empty,
bool plan_only)
138 switch (error_code.val)
140 case moveit_msgs::msg::MoveItErrorCodes::SUCCESS:
141 if (planned_trajectory_empty)
143 return "Requested path and goal constraints are already met.";
149 return "Motion plan was computed successfully.";
153 return "Solution was found and executed.";
156 case moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME:
157 return "Invalid group in motion plan request";
158 case moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED:
159 case moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN:
160 if (planned_trajectory_empty)
162 return "No motion plan found. No execution attempted.";
166 return "Motion plan was found but it seems to be invalid (possibly due to postprocessing). Not executing.";
168 case moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA:
169 return "Motion plan was found but it seems to be too costly and looking around did not help.";
170 case moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE:
171 return "Solution found but the environment changed during execution and the path was aborted";
195 const std::string& target_frame)
const
199 if (pose_msg.header.frame_id == target_frame)
201 if (pose_msg.header.frame_id.empty())
203 pose_msg.header.frame_id = target_frame;
209 geometry_msgs::msg::TransformStamped common_tf =
context_->planning_scene_monitor_->getTFClient()->lookupTransform(
210 pose_msg.header.frame_id, target_frame, rclcpp::Time(0.0));
211 geometry_msgs::msg::PoseStamped pose_msg_in(pose_msg);
212 pose_msg_in.header.stamp = common_tf.header.stamp;
213 context_->planning_scene_monitor_->getTFClient()->transform(pose_msg_in, pose_msg, target_frame);
215 catch (tf2::TransformException& ex)
217 RCLCPP_ERROR(getLogger(),
"TF Problem: %s", ex.what());
225 if (pipeline_id.empty())
228 return context_->planning_pipeline_;
235 auto pipeline =
context_->moveit_cpp_->getPlanningPipelines().at(pipeline_id);
236 RCLCPP_INFO(getLogger(),
"Using planning pipeline '%s'", pipeline_id.c_str());
239 catch (
const std::out_of_range&)
241 RCLCPP_WARN(getLogger(),
"Couldn't find requested planning pipeline '%s'", pipeline_id.c_str());
245 return planning_pipeline::PlanningPipelinePtr();
void setContext(const MoveGroupContextPtr &context)
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
bool performTransform(geometry_msgs::msg::PoseStamped &pose_msg, const std::string &target_frame) const
MoveGroupContextPtr context_
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
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.
std::string errorCodeToString(const MoveItErrorCode &error_code)
Convenience function to translated error message into string.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest