Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <moveit/move_group/move_group_capability.h>
00038 #include <moveit/robot_state/conversions.h>
00039
00040 void move_group::MoveGroupCapability::setContext(const MoveGroupContextPtr &context)
00041 {
00042 context_ = context;
00043 }
00044
00045 void move_group::MoveGroupCapability::convertToMsg(const std::vector<plan_execution::ExecutableTrajectory> &trajectory,
00046 moveit_msgs::RobotState &first_state_msg, std::vector<moveit_msgs::RobotTrajectory> &trajectory_msg) const
00047 {
00048 if (!trajectory.empty())
00049 {
00050 bool first = true;
00051 trajectory_msg.resize(trajectory.size());
00052 for (std::size_t i = 0 ; i < trajectory.size() ; ++i)
00053 {
00054 if (trajectory[i].trajectory_)
00055 {
00056 if (first && !trajectory[i].trajectory_->empty())
00057 {
00058 robot_state::robotStateToRobotStateMsg(trajectory[i].trajectory_->getFirstWayPoint(), first_state_msg);
00059 first = false;
00060 }
00061 trajectory[i].trajectory_->getRobotTrajectoryMsg(trajectory_msg[i]);
00062 }
00063 }
00064 }
00065 }
00066
00067 void move_group::MoveGroupCapability::convertToMsg(const robot_trajectory::RobotTrajectoryPtr &trajectory,
00068 moveit_msgs::RobotState &first_state_msg, moveit_msgs::RobotTrajectory &trajectory_msg) const
00069 {
00070 if (trajectory && !trajectory->empty())
00071 {
00072 robot_state::robotStateToRobotStateMsg(trajectory->getFirstWayPoint(), first_state_msg);
00073 trajectory->getRobotTrajectoryMsg(trajectory_msg);
00074 }
00075 }
00076
00077 void move_group::MoveGroupCapability::convertToMsg(const std::vector<plan_execution::ExecutableTrajectory> &trajectory,
00078 moveit_msgs::RobotState &first_state_msg, moveit_msgs::RobotTrajectory &trajectory_msg) const
00079 {
00080 if (trajectory.size() > 1)
00081 ROS_ERROR_STREAM("Internal logic error: trajectory component ignored. !!! THIS IS A SERIOUS ERROR !!!");
00082 if (trajectory.size() > 0)
00083 convertToMsg(trajectory[0].trajectory_, first_state_msg,trajectory_msg);
00084 }
00085
00086 planning_interface::MotionPlanRequest move_group::MoveGroupCapability::clearRequestStartState(const planning_interface::MotionPlanRequest &request) const
00087 {
00088 planning_interface::MotionPlanRequest r = request;
00089 r.start_state = moveit_msgs::RobotState();
00090 ROS_WARN("Execution of motions should always start at the robot's current state. Ignoring the state supplied as start state in the motion planning request");
00091 return r;
00092 }
00093
00094 moveit_msgs::PlanningScene move_group::MoveGroupCapability::clearSceneRobotState(const moveit_msgs::PlanningScene &scene) const
00095 {
00096 moveit_msgs::PlanningScene r = scene;
00097 r.robot_state = moveit_msgs::RobotState();
00098 ROS_WARN("Execution of motions should always start at the robot's current state. Ignoring the state supplied as difference in the planning scene diff");
00099 return r;
00100 }
00101
00102 std::string move_group::MoveGroupCapability::getActionResultString(const moveit_msgs::MoveItErrorCodes &error_code, bool planned_trajectory_empty, bool plan_only)
00103 {
00104 if (error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
00105 {
00106 if (planned_trajectory_empty)
00107 return "Requested path and goal constraints are already met.";
00108 else
00109 {
00110 if (plan_only)
00111 return "Motion plan was computed succesfully.";
00112 else
00113 return "Solution was found and executed.";
00114 }
00115 }
00116 else
00117 if (error_code.val == moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME)
00118 return "Must specify group in motion plan request";
00119 else
00120 if (error_code.val == moveit_msgs::MoveItErrorCodes::PLANNING_FAILED || error_code.val == moveit_msgs::MoveItErrorCodes::INVALID_MOTION_PLAN)
00121 {
00122 if (planned_trajectory_empty)
00123 return "No motion plan found. No execution attempted.";
00124 else
00125 return "Motion plan was found but it seems to be invalid (possibly due to postprocessing). Not executing.";
00126 }
00127 else
00128 if (error_code.val == moveit_msgs::MoveItErrorCodes::UNABLE_TO_AQUIRE_SENSOR_DATA)
00129 return "Motion plan was found but it seems to be too costly and looking around did not help.";
00130 else
00131 if (error_code.val == moveit_msgs::MoveItErrorCodes::MOTION_PLAN_INVALIDATED_BY_ENVIRONMENT_CHANGE)
00132 return "Solution found but the environment changed during execution and the path was aborted";
00133 else
00134 if (error_code.val == moveit_msgs::MoveItErrorCodes::CONTROL_FAILED)
00135 return "Solution found but controller failed during execution";
00136 else
00137 if (error_code.val == moveit_msgs::MoveItErrorCodes::TIMED_OUT)
00138 return "Timeout reached";
00139 else
00140 if (error_code.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
00141 return "Preempted";
00142 else
00143 if (error_code.val == moveit_msgs::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS)
00144 return "Invalid goal constraints";
00145 else
00146 if (error_code.val == moveit_msgs::MoveItErrorCodes::INVALID_GROUP_NAME)
00147 return "Invalid group name";
00148 else
00149 if (error_code.val == moveit_msgs::MoveItErrorCodes::INVALID_OBJECT_NAME)
00150 return "Invalid object name";
00151 else
00152 if (error_code.val == moveit_msgs::MoveItErrorCodes::FAILURE)
00153 return "Catastrophic failure";
00154 return "Unknown event";
00155 }
00156
00157 std::string move_group::MoveGroupCapability::stateToStr(MoveGroupState state) const
00158 {
00159 switch (state)
00160 {
00161 case IDLE:
00162 return "IDLE";
00163 case PLANNING:
00164 return "PLANNING";
00165 case MONITOR:
00166 return "MONITOR";
00167 case LOOK:
00168 return "LOOK";
00169 default:
00170 return "UNKNOWN";
00171 }
00172 }
00173
00174 bool move_group::MoveGroupCapability::performTransform(geometry_msgs::PoseStamped &pose_msg, const std::string &target_frame) const
00175 {
00176 if (!context_ || !context_->planning_scene_monitor_->getTFClient())
00177 return false;
00178 if (pose_msg.header.frame_id == target_frame)
00179 return true;
00180 if (pose_msg.header.frame_id.empty())
00181 {
00182 pose_msg.header.frame_id = target_frame;
00183 return true;
00184 }
00185
00186 try
00187 {
00188 std::string error;
00189 ros::Time common_time;
00190 context_->planning_scene_monitor_->getTFClient()->getLatestCommonTime(pose_msg.header.frame_id, target_frame, common_time, &error);
00191 if (!error.empty())
00192 ROS_ERROR("TF Problem: %s", error.c_str());
00193
00194 tf::Stamped<tf::Pose> pose_tf, pose_tf_out;
00195 tf::poseStampedMsgToTF(pose_msg, pose_tf);
00196 pose_tf.stamp_ = common_time;
00197 context_->planning_scene_monitor_->getTFClient()->transformPose(target_frame, pose_tf, pose_tf_out);
00198 tf::poseStampedTFToMsg(pose_tf_out, pose_msg);
00199 }
00200 catch (tf::TransformException &ex)
00201 {
00202 ROS_ERROR("TF Problem: %s", ex.what());
00203 return false;
00204 }
00205 return true;
00206 }