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 "execute_trajectory_action_capability.h"
00038
00039 #include <moveit/plan_execution/plan_execution.h>
00040 #include <moveit/trajectory_processing/trajectory_tools.h>
00041 #include <moveit/kinematic_constraints/utils.h>
00042 #include <moveit/move_group/capability_names.h>
00043
00044 namespace move_group
00045 {
00046 MoveGroupExecuteTrajectoryAction::MoveGroupExecuteTrajectoryAction() : MoveGroupCapability("ExecuteTrajectoryAction")
00047 {
00048 }
00049
00050 void MoveGroupExecuteTrajectoryAction::initialize()
00051 {
00052
00053 execute_action_server_.reset(new actionlib::SimpleActionServer<moveit_msgs::ExecuteTrajectoryAction>(
00054 root_node_handle_, EXECUTE_ACTION_NAME,
00055 boost::bind(&MoveGroupExecuteTrajectoryAction::executePathCallback, this, _1), false));
00056 execute_action_server_->registerPreemptCallback(
00057 boost::bind(&MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback, this));
00058 execute_action_server_->start();
00059 }
00060
00061 void MoveGroupExecuteTrajectoryAction::executePathCallback(const moveit_msgs::ExecuteTrajectoryGoalConstPtr& goal)
00062 {
00063 moveit_msgs::ExecuteTrajectoryResult action_res;
00064 if (!context_->trajectory_execution_manager_)
00065 {
00066 std::string response = "Cannot execute trajectory since ~allow_trajectory_execution was set to false";
00067 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
00068 execute_action_server_->setAborted(action_res, response);
00069 return;
00070 }
00071
00072 executePathCallback_Execute(goal, action_res);
00073
00074 std::string response = getActionResultString(action_res.error_code, false, false);
00075 if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::SUCCESS)
00076 {
00077 execute_action_server_->setSucceeded(action_res, response);
00078 }
00079 else if (action_res.error_code.val == moveit_msgs::MoveItErrorCodes::PREEMPTED)
00080 {
00081 execute_action_server_->setPreempted(action_res, response);
00082 }
00083 else
00084 {
00085 execute_action_server_->setAborted(action_res, response);
00086 }
00087
00088 setExecuteTrajectoryState(IDLE);
00089 }
00090
00091 void MoveGroupExecuteTrajectoryAction::executePathCallback_Execute(
00092 const moveit_msgs::ExecuteTrajectoryGoalConstPtr& goal, moveit_msgs::ExecuteTrajectoryResult& action_res)
00093 {
00094 ROS_INFO_NAMED("move_group", "Execution request received for ExecuteTrajectory action.");
00095
00096 context_->trajectory_execution_manager_->clear();
00097 if (context_->trajectory_execution_manager_->push(goal->trajectory))
00098 {
00099 setExecuteTrajectoryState(MONITOR);
00100 context_->trajectory_execution_manager_->execute();
00101 moveit_controller_manager::ExecutionStatus es = context_->trajectory_execution_manager_->waitForExecution();
00102 if (es == moveit_controller_manager::ExecutionStatus::SUCCEEDED)
00103 {
00104 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::SUCCESS;
00105 }
00106 else if (es == moveit_controller_manager::ExecutionStatus::PREEMPTED)
00107 {
00108 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::PREEMPTED;
00109 }
00110 else if (es == moveit_controller_manager::ExecutionStatus::TIMED_OUT)
00111 {
00112 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::TIMED_OUT;
00113 }
00114 else
00115 {
00116 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
00117 }
00118 ROS_INFO_STREAM_NAMED("move_group", "Execution completed: " << es.asString());
00119 }
00120 else
00121 {
00122 action_res.error_code.val = moveit_msgs::MoveItErrorCodes::CONTROL_FAILED;
00123 }
00124 }
00125
00126 void MoveGroupExecuteTrajectoryAction::preemptExecuteTrajectoryCallback()
00127 {
00128 context_->trajectory_execution_manager_->stopExecution(true);
00129 }
00130
00131 void MoveGroupExecuteTrajectoryAction::setExecuteTrajectoryState(MoveGroupState state)
00132 {
00133 moveit_msgs::ExecuteTrajectoryFeedback execute_feedback;
00134 execute_feedback.state = stateToStr(state);
00135 execute_action_server_->publishFeedback(execute_feedback);
00136 }
00137
00138 }
00139
00140 #include <class_loader/class_loader.h>
00141 CLASS_LOADER_REGISTER_CLASS(move_group::MoveGroupExecuteTrajectoryAction, move_group::MoveGroupCapability)