52 moveit_msgs::RobotState& first_state_msg,
53 std::vector<moveit_msgs::RobotTrajectory>& trajectory_msg)
const
55 if (!trajectory.empty())
58 trajectory_msg.resize(trajectory.size());
59 for (std::size_t i = 0; i < trajectory.size(); ++i)
61 if (trajectory[i].trajectory_)
63 if (first && !trajectory[i].trajectory_->empty())
68 trajectory[i].trajectory_->getRobotTrajectoryMsg(trajectory_msg[i]);
75 moveit_msgs::RobotState& first_state_msg,
76 moveit_msgs::RobotTrajectory& trajectory_msg)
const
78 if (trajectory && !trajectory->empty())
81 trajectory->getRobotTrajectoryMsg(trajectory_msg);
86 moveit_msgs::RobotState& first_state_msg,
87 moveit_msgs::RobotTrajectory& trajectory_msg)
const
89 if (trajectory.size() > 1)
90 ROS_ERROR_STREAM(
"Internal logic error: trajectory component ignored. !!! THIS IS A SERIOUS ERROR !!!");
91 if (!trajectory.empty())
92 convertToMsg(trajectory[0].trajectory_, first_state_msg, trajectory_msg);
99 r.start_state = moveit_msgs::RobotState();
100 r.start_state.is_diff =
true;
101 ROS_WARN(
"Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
102 "start state in the motion planning request");
106 moveit_msgs::PlanningScene
109 moveit_msgs::PlanningScene
r = scene;
110 r.robot_state = moveit_msgs::RobotState();
111 r.robot_state.is_diff =
true;
112 ROS_WARN(
"Execution of motions should always start at the robot's current state. Ignoring the state supplied as "
113 "difference in the planning scene diff");
118 bool planned_trajectory_empty,
bool plan_only)
120 switch (error_code.val)
122 case moveit_msgs::MoveItErrorCodes::SUCCESS:
123 if (planned_trajectory_empty)
124 return "Requested path and goal constraints are already met.";
128 return "Motion plan was computed succesfully.";
130 return "Solution was found and executed.";
132 case moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME:
133 return "Invalid group in motion plan request";
134 case moveit_msgs::MoveItErrorCodes::PLANNING_FAILED:
135 case moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN:
136 if (planned_trajectory_empty)
137 return "No motion plan found. No execution attempted.";
139 return "Motion plan was found but it seems to be invalid (possibly due to postprocessing). Not executing.";
140 case moveit_msgs::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA:
141 return "Motion plan was found but it seems to be too costly and looking around did not help.";
142 case moveit_msgs::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE:
143 return "Solution found but the environment changed during execution and the path was aborted";
167 const std::string& target_frame)
const
169 if (!context_ || !context_->planning_scene_monitor_->getTFClient())
171 if (pose_msg.header.frame_id == target_frame)
173 if (pose_msg.header.frame_id.empty())
175 pose_msg.header.frame_id = target_frame;
181 geometry_msgs::TransformStamped common_tf = context_->planning_scene_monitor_->getTFClient()->lookupTransform(
182 pose_msg.header.frame_id, target_frame,
ros::Time(0.0));
183 geometry_msgs::PoseStamped pose_msg_in(pose_msg);
184 pose_msg_in.header.stamp = common_tf.header.stamp;
185 context_->planning_scene_monitor_->getTFClient()->transform(pose_msg_in, pose_msg, target_frame);
195 planning_pipeline::PlanningPipelinePtr
198 if (pipeline_id.empty())
201 return context_->planning_pipeline_;
208 auto pipeline = context_->moveit_cpp_->getPlanningPipelines().at(pipeline_id);
212 catch (
const std::out_of_range&)
218 return planning_pipeline::PlanningPipelinePtr();