40 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
45 static const rclcpp::Logger
LOGGER = rclcpp::get_logger(
"moveit_move_group_capabilities_base.move_group_capability");
53 moveit_msgs::msg::RobotState& first_state_msg,
54 std::vector<moveit_msgs::msg::RobotTrajectory>& trajectory_msg)
const
56 if (!trajectory.empty())
59 trajectory_msg.resize(trajectory.size());
60 for (std::size_t i = 0; i < trajectory.size(); ++i)
62 if (trajectory[i].trajectory_)
64 if (first && !trajectory[i].trajectory_->empty())
69 trajectory[i].trajectory_->getRobotTrajectoryMsg(trajectory_msg[i]);
76 moveit_msgs::msg::RobotState& first_state_msg,
77 moveit_msgs::msg::RobotTrajectory& trajectory_msg)
const
79 if (trajectory && !trajectory->empty())
82 trajectory->getRobotTrajectoryMsg(trajectory_msg);
87 moveit_msgs::msg::RobotState& first_state_msg,
88 moveit_msgs::msg::RobotTrajectory& trajectory_msg)
const
90 if (trajectory.size() > 1)
91 RCLCPP_ERROR_STREAM(LOGGER,
"Internal logic error: trajectory component ignored. !!! THIS IS A SERIOUS ERROR !!!");
92 if (!trajectory.empty())
93 convertToMsg(trajectory[0].trajectory_, first_state_msg, trajectory_msg);
100 r.start_state = moveit_msgs::msg::RobotState();
101 r.start_state.is_diff =
true;
103 "Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
104 "start state in the motion planning request");
108 moveit_msgs::msg::PlanningScene
111 moveit_msgs::msg::PlanningScene
r =
scene;
112 r.robot_state = moveit_msgs::msg::RobotState();
113 r.robot_state.is_diff =
true;
115 "Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
116 "difference in the planning scene diff");
121 bool planned_trajectory_empty,
bool plan_only)
123 if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
125 if (planned_trajectory_empty)
126 return "Requested path and goal constraints are already met.";
130 return "Motion plan was computed successfully.";
132 return "Solution was found and executed.";
135 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME)
136 return "Must specify group in motion plan request";
137 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED ||
138 error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
140 if (planned_trajectory_empty)
141 return "No motion plan found. No execution attempted.";
143 return "Motion plan was found but it seems to be invalid (possibly due to postprocessing). Not executing.";
145 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA)
146 return "Motion plan was found but it seems to be too costly and looking around did not help.";
147 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
148 return "Solution found but the environment changed during execution and the path was aborted";
149 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED)
150 return "Solution found but controller failed during execution";
151 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::TIMED_OUT)
152 return "Timeout reached";
153 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::PREEMPTED)
155 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
156 return "Invalid goal constraints";
157 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::INVALID_OBJECT_NAME)
158 return "Invalid object name";
159 else if (error_code.val == moveit_msgs::msg::MoveItErrorCodes::FAILURE)
160 return "Catastrophic failure";
161 return "Unknown event";
182 const std::string& target_frame)
const
184 if (!context_ || !context_->planning_scene_monitor_->getTFClient())
186 if (pose_msg.header.frame_id == target_frame)
188 if (pose_msg.header.frame_id.empty())
190 pose_msg.header.frame_id = target_frame;
196 geometry_msgs::msg::TransformStamped common_tf = context_->planning_scene_monitor_->getTFClient()->lookupTransform(
197 pose_msg.header.frame_id, target_frame, rclcpp::Time(0.0));
198 geometry_msgs::msg::PoseStamped pose_msg_in(pose_msg);
199 pose_msg_in.header.stamp = common_tf.header.stamp;
200 context_->planning_scene_monitor_->getTFClient()->transform(pose_msg_in, pose_msg, target_frame);
202 catch (tf2::TransformException& ex)
204 RCLCPP_ERROR(LOGGER,
"TF Problem: %s", ex.what());
210 planning_pipeline::PlanningPipelinePtr
213 if (pipeline_id.empty())
216 return context_->planning_pipeline_;
223 auto pipeline = context_->moveit_cpp_->getPlanningPipelines().at(pipeline_id);
224 RCLCPP_INFO(LOGGER,
"Using planning pipeline '%s'", pipeline_id.c_str());
227 catch (
const std::out_of_range&)
229 RCLCPP_WARN(LOGGER,
"Couldn't find requested planning pipeline '%s'", pipeline_id.c_str());
233 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
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.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
const rclcpp::Logger LOGGER