Skip to content

Commit

Permalink
Added an action definition for use with the tool contact controller (…
Browse files Browse the repository at this point in the history
…WIP)
  • Loading branch information
URJala committed Jan 14, 2025
1 parent 27da72c commit 6bf35ab
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 0 deletions.
5 changes: 5 additions & 0 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,10 @@ set(srv_files
srv/SetForceMode.srv
)

set(action_files
action/ToolContact.action
)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand All @@ -33,6 +37,7 @@ endif()
rosidl_generate_interfaces(${PROJECT_NAME}
${msg_files}
${srv_files}
${action_files}
DEPENDENCIES builtin_interfaces geometry_msgs
ADD_LINTER_TESTS
)
Expand Down
8 changes: 8 additions & 0 deletions action/ToolContact.action
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@

---
uint8 SUCCESS=1
uint8 CANCELLED_BY_USER=2
uint8 ABORTED_BY_HARDWARE=3
uint8 ABORTED_BY_CONTROLLER=4
uint8 result
---
1 change: 1 addition & 0 deletions package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

<depend>builtin_interfaces</depend>
<depend>geometry_msgs</depend>
<depend>action_msgs</depend>

<exec_depend>rosidl_default_runtime</exec_depend>

Expand Down

0 comments on commit 6bf35ab

Please sign in to comment.