From fd41eeb67986cee953e307fc25297ae1858b0ee4 Mon Sep 17 00:00:00 2001 From: Kentaro Wada Date: Mon, 18 Jul 2016 22:38:40 +0900 Subject: [PATCH] Add .action file for execution trajectory in a ROS action --- CMakeLists.txt | 1 + action/ExecuteKnownTrajectory.action | 18 ++++++++++++++++++ 2 files changed, 19 insertions(+) create mode 100644 action/ExecuteKnownTrajectory.action diff --git a/CMakeLists.txt b/CMakeLists.txt index c325b10..5af26ac 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -77,6 +77,7 @@ DeleteRobotStateFromWarehouse.srv ) set(ACT_FILES +ExecuteKnownTrajectory.action MoveGroup.action Pickup.action Place.action diff --git a/action/ExecuteKnownTrajectory.action b/action/ExecuteKnownTrajectory.action new file mode 100644 index 0000000..c5b4f78 --- /dev/null +++ b/action/ExecuteKnownTrajectory.action @@ -0,0 +1,18 @@ +# The trajectory to execute +RobotTrajectory trajectory + +--- + +# Error code - encodes the overall reason for failure +MoveItErrorCodes error_code + +# The full starting state of the robot at the start of the trajectory +moveit_msgs/RobotState trajectory_start + +# The trace of the trajectory recorded during execution +moveit_msgs/RobotTrajectory executed_trajectory + +--- + +# The internal state that the move group action currently is in +string state