Skip to content

Commit

Permalink
Add .action file for execution trajectory in a ROS action
Browse files Browse the repository at this point in the history
  • Loading branch information
wkentaro committed Jul 18, 2016
1 parent 9640de4 commit fd41eeb
Show file tree
Hide file tree
Showing 2 changed files with 19 additions and 0 deletions.
1 change: 1 addition & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,7 @@ DeleteRobotStateFromWarehouse.srv
)

set(ACT_FILES
ExecuteKnownTrajectory.action
MoveGroup.action
Pickup.action
Place.action
Expand Down
18 changes: 18 additions & 0 deletions action/ExecuteKnownTrajectory.action
Original file line number Diff line number Diff line change
@@ -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

0 comments on commit fd41eeb

Please # to comment.