ardupilot/Tools/ros2/ardupilot_msgs/CMakeLists.txt
arshPratap e0f5e30985 Tools: add custom ROS 2 messages and service interfaces
- Moved from https://github.com/arshPratap/ardupilot_ros2.
- Document interface.

Signed-off-by: Rhys Mainwaring <rhys.mainwaring@me.com>
2023-07-19 16:36:28 +09:00

24 lines
619 B
CMake

cmake_minimum_required(VERSION 3.8)
project(ardupilot_msgs)
# --------------------------------------------------------------------------- #
# Find dependencies.
find_package(ament_cmake REQUIRED)
find_package(rosidl_default_generators REQUIRED)
# --------------------------------------------------------------------------- #
# Generate and export message interfaces.
rosidl_generate_interfaces(${PROJECT_NAME}
"srv/ArmMotors.srv"
ADD_LINTER_TESTS
)
ament_export_dependencies(rosidl_default_runtime)
# --------------------------------------------------------------------------- #
# Call last.
ament_package()