From 1e4b9aa0839f329aab51f066ace06a4de8cfcd07 Mon Sep 17 00:00:00 2001 From: Vincenzo Di Pentima Date: Thu, 17 Oct 2024 09:09:03 +0000 Subject: [PATCH] Added action for enabling freedrive mode --- CMakeLists.txt | 5 +++++ action/EnableFreedriveMode.action | 5 +++++ 2 files changed, 10 insertions(+) create mode 100644 action/EnableFreedriveMode.action diff --git a/CMakeLists.txt b/CMakeLists.txt index 8015c6e..d28deeb 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -6,6 +6,10 @@ find_package(builtin_interfaces REQUIRED) find_package(rosidl_default_generators REQUIRED) find_package(geometry_msgs REQUIRED) +set(action_files + action/EnableFreedriveMode.action +) + set(msg_files msg/Analog.msg msg/Digital.msg @@ -30,6 +34,7 @@ if(BUILD_TESTING) endif() rosidl_generate_interfaces(${PROJECT_NAME} + ${action_files} ${msg_files} ${srv_files} DEPENDENCIES builtin_interfaces geometry_msgs diff --git a/action/EnableFreedriveMode.action b/action/EnableFreedriveMode.action new file mode 100644 index 0000000..f59a71d --- /dev/null +++ b/action/EnableFreedriveMode.action @@ -0,0 +1,5 @@ +# Action to enable freedrive mode +# once the FreedriveModeController is active +--- +--- +