From e3245b00f02bd2d43099ecebfcb9b2eb6bfec9a2 Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 3 Jan 2025 13:54:14 +0100 Subject: [PATCH 1/6] Document package conventions. Signed-off-by: Jelmer de Wolde --- .../ros_msgs_package/CMakeLists.txt | 31 +++++++ .../example_files/ros_package/CMakeLists.txt | 41 +++++++++ .../example_files/ros_package/package.xml | 21 +++++ docs/content/conventions/ros_package.md | 89 +++++++++++++++++++ docs/content/conventions/ros_package_msgs.md | 47 ++++++++++ docs/index.rst | 3 + 6 files changed, 232 insertions(+) create mode 100644 docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt create mode 100644 docs/content/conventions/example_files/ros_package/CMakeLists.txt create mode 100644 docs/content/conventions/example_files/ros_package/package.xml create mode 100644 docs/content/conventions/ros_package.md create mode 100644 docs/content/conventions/ros_package_msgs.md diff --git a/docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt b/docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt new file mode 100644 index 0000000..ef700fc --- /dev/null +++ b/docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt @@ -0,0 +1,31 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_package) + +# CMake dependencies: +find_package(ament_cmake REQUIRED) +find_package(rosidl_default_generators REQUIRED) + +# Other dependencies: +find_package(geometry_msgs REQUIRED) +find_package(vision_msgs REQUIRED) + +# Service definitions: +file(GLOB SRVS CONFIGURE_DEPENDS srv/*.srv*) + +foreach(file IN LISTS SRVS) + string(REPLACE "${CMAKE_CURRENT_SOURCE_DIR}/" "" file_relative ${file}) + list(APPEND SRVS_STRIPPED ${file_relative}) +endforeach() + +rosidl_generate_interfaces(${PROJECT_NAME} + ${SRVS_STRIPPED} + DEPENDENCIES geometry_msgs vision_msgs +) + +# Default test: +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() \ No newline at end of file diff --git a/docs/content/conventions/example_files/ros_package/CMakeLists.txt b/docs/content/conventions/example_files/ros_package/CMakeLists.txt new file mode 100644 index 0000000..7cb9a11 --- /dev/null +++ b/docs/content/conventions/example_files/ros_package/CMakeLists.txt @@ -0,0 +1,41 @@ +cmake_minimum_required(VERSION 3.5) +project(ros_package) + +# CMake dependencies: +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) + +# Other dependencies: +find_package(geometry_msgs REQUIRED) +find_package(vision_msgs REQUIRED) + +# C++ executables: +add_executable(cpp_node src/cpp_node.cpp) +ament_target_dependencies(cpp_node geometry_msgs vision_msgs) +install( + TARGETS cpp_node + DESTINATION lib/${PROJECT_NAME} +) + +# Python executables: +install( + DIRECTORY src_py/ + DESTINATION lib/${PROJECT_NAME} +) + +# Python package: +ament_python_install_package(${PROJECT_NAME}) + +# Shared folders: +install( + DIRECTORY launch + DESTINATION share/${PROJECT_NAME} +) + +# Default test: +if(BUILD_TESTING) + find_package(ament_lint_auto REQUIRED) + ament_lint_auto_find_test_dependencies() +endif() + +ament_package() \ No newline at end of file diff --git a/docs/content/conventions/example_files/ros_package/package.xml b/docs/content/conventions/example_files/ros_package/package.xml new file mode 100644 index 0000000..8d258a0 --- /dev/null +++ b/docs/content/conventions/example_files/ros_package/package.xml @@ -0,0 +1,21 @@ + + + + ros_package + 0.1.0 + A ros package. + RCDT + Apache 2.0 + + ament_cmake + ament_cmake_python + + geometry_msgs + vision_msgs + + ament_lint_auto + + + ament_cmake + + \ No newline at end of file diff --git a/docs/content/conventions/ros_package.md b/docs/content/conventions/ros_package.md new file mode 100644 index 0000000..985af00 --- /dev/null +++ b/docs/content/conventions/ros_package.md @@ -0,0 +1,89 @@ +# ros_package conventions + +## Folder Structure + +We try to follow this folder structure for the ROS packages: + +```text +ros_package/ +| CMakeLists.txt +| package.xml +| +└───src/ +| | cpp_node.cpp +| +└───include/ +| └───ros_package/ +| | cpp_header.hpp +| +└───src_py/ +| | py_node.py +| +└───ros_package/ +| | __init__.py +| | py_module.py +| +└───launch/ + | launch_file.launch.py +``` + +- Every ROS package contains the `CMakeLists.txt` and `package.xml` in the root directory. +- In case of development using C++, the executables are located in the `src/` directory. The corresponding headers are located in the `include/` directory, inside a sub-directory that equals the package name. +- In case of development using Python, the executables are located in the `src_py/` directory. +- A sub-directory `ros_package/` with the same name as the ROS package can be used to create a Python package. This directory contains an `__init__.py` file and the Python modules of the Python package. +- Possible launch files are located in the `launch/` directory. +- More directories are possible, like `urdf/` for urdf files or `config/` for config files. + +## CMakeLists.txt + +This CMakeLists.txt file shows the different parts required to build a ROS package: + +:::{literalinclude} example_files/ros_package/CMakeLists.txt +:language: CMake +:linenos: +::: + +**1-6**:\ +The file always starts with a version definition, the package name and the CMake dependencies when building C++ and/or python files. + +**8-10**:\ +If the package depends on other packages, these are defined. In this case, the packaged depends on the *vision_msgs* and *geometry_msgs* packages. + +**12-18**:\ +Building a C++ executable requires 3 steps: defining the executable, linking dependencies (if any) and installing the targets to the lib directory. + +**20-24**:\ +For Python executables, we can simply install them all at the same time, by providing the directory. + +**26-27**:\ +If the package contains a Python package, it needs to be installed. + +**29-33**\ +All shared folders are installed into the share directory. This includes the directory of launch files, but also other possible directories, like `urdf/` or `config/`, if these exist. + +**35-41**:\ +The file always ends with a default test and the *ament_package()* command. + +## package.xml + +The package.xml file is related to the CMakeLists.txt file: + +:::{literalinclude} example_files/ros_package/package.xml +:language: xml +:linenos: +::: + +**1-2**:\ +The files starts with default xml definitions. + +**3-8**:\ +Inside the *package* tag, we start with some general information about the package. + +**10-11**:\ +Next, we define the build tool dependencies for building C++ and/or Python files. + +**13-14**:\ +Next, we define other packages where our package depends on. + +**16-21**"\ +The file ends with the default test dependency and an export definition. diff --git a/docs/content/conventions/ros_package_msgs.md b/docs/content/conventions/ros_package_msgs.md new file mode 100644 index 0000000..218c177 --- /dev/null +++ b/docs/content/conventions/ros_package_msgs.md @@ -0,0 +1,47 @@ +# ros_package_msgs conventions + +## Folder Structure + +We define custom messages, services and actions in a separate package, with a package name ending on *_msgs*, to avoid build problems. This package has the following folder structure: + +```text +ros_package/ +| CMakeLists.txt +| package.xml +| +└───srv/ +| | custom_service_definition.srv +| +└───msg/ +└───action/ +``` + +- The structure is very similar to a normal ROS package. +- There is a *srv*, *msg* and/or *action* directory for custom service/message/action definitions. + +## CMakeLists.txt + +Also the CMakeLists.txt file is very similar. This shows an example where only custom services are generated, but the procedure for custom messages or actions is very similar: + +:::{literalinclude} example_files/ros_msgs_package/CMakeLists.txt +:language: CMake +:linenos: +::: + +**6**:\ +The *rosidl_default_generators* dependency is now required, to generated the custom messages. + +**13-18**:\ +We use CMake's *GLOB* method to automatically obtain all the srv files. + +**20-23**:\ +We generate the custom service and link the dependencies (if any). + +## package.xml + +To generate custom messages successfully, we also need to specify the following dependencies in the package.xml file: + +```xml + rosidl_default_generators + rosidl_interface_packages +``` diff --git a/docs/index.rst b/docs/index.rst index 19eeb35..93c4080 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -17,6 +17,9 @@ Home content/getting_started.md + content/conventions/ros_package.md + content/conventions/ros_package_msgs.md + content/pyflow.md content/docker.md content/writing_documentation.md From ba4f8e97e8a866aabb1915102755966e1b7ca666 Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 3 Jan 2025 14:06:38 +0100 Subject: [PATCH 2/6] Apply cmake conventions from docs. Signed-off-by: Jelmer de Wolde --- ros2_ws/src/rcdt_detection/CMakeLists.txt | 25 +++++++++------- .../{nodes => src_py}/get_mask_properties.py | 0 .../get_rgbd_from_topic_node.py | 0 .../{nodes => src_py}/pose_from_pixel_node.py | 0 .../{nodes => src_py}/publish_image_node.py | 0 .../{nodes => src_py}/publish_masks_node.py | 0 .../{nodes => src_py}/segment_image_node.py | 0 .../select_image_from_list_node.py | 0 .../select_pick_location_node.py | 0 ros2_ws/src/rcdt_franka/CMakeLists.txt | 15 +++++----- .../{nodes => src_py}/close_gripper_node.py | 0 .../franka_gripper_simulation_node.py | 0 .../{nodes => src_py}/joy_to_gripper_node.py | 0 .../{nodes => src_py}/open_gripper_node.py | 0 .../{nodes => src_py}/settings_setter_node.py | 0 ros2_ws/src/rcdt_gz_worlds/CMakeLists.txt | 5 ++-- .../rcdt_mobile_manipulator/CMakeLists.txt | 15 +++++----- .../joy_topic_manager_node.py | 0 ros2_ws/src/rcdt_panther/CMakeLists.txt | 5 ++-- ros2_ws/src/rcdt_sensors/CMakeLists.txt | 16 +++++----- .../combine_camera_topics_node.py | 0 .../convert_32FC1_to_16UC1_node.py | 0 ros2_ws/src/rcdt_utilities/CMakeLists.txt | 29 ++++++++++--------- .../{nodes => src_py}/joy_to_twist_node.py | 0 .../{nodes => src_py}/manipulate_pose_node.py | 0 .../moveit_controller_node.py | 0 26 files changed, 60 insertions(+), 50 deletions(-) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/get_mask_properties.py (100%) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/get_rgbd_from_topic_node.py (100%) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/pose_from_pixel_node.py (100%) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/publish_image_node.py (100%) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/publish_masks_node.py (100%) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/segment_image_node.py (100%) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/select_image_from_list_node.py (100%) rename ros2_ws/src/rcdt_detection/{nodes => src_py}/select_pick_location_node.py (100%) rename ros2_ws/src/rcdt_franka/{nodes => src_py}/close_gripper_node.py (100%) rename ros2_ws/src/rcdt_franka/{nodes => src_py}/franka_gripper_simulation_node.py (100%) rename ros2_ws/src/rcdt_franka/{nodes => src_py}/joy_to_gripper_node.py (100%) rename ros2_ws/src/rcdt_franka/{nodes => src_py}/open_gripper_node.py (100%) rename ros2_ws/src/rcdt_franka/{nodes => src_py}/settings_setter_node.py (100%) rename ros2_ws/src/rcdt_mobile_manipulator/{nodes => src_py}/joy_topic_manager_node.py (100%) rename ros2_ws/src/rcdt_sensors/{nodes => src_py}/combine_camera_topics_node.py (100%) rename ros2_ws/src/rcdt_sensors/{nodes => src_py}/convert_32FC1_to_16UC1_node.py (100%) rename ros2_ws/src/rcdt_utilities/{nodes => src_py}/joy_to_twist_node.py (100%) rename ros2_ws/src/rcdt_utilities/{nodes => src_py}/manipulate_pose_node.py (100%) rename ros2_ws/src/rcdt_utilities/{nodes => src_py}/moveit_controller_node.py (100%) diff --git a/ros2_ws/src/rcdt_detection/CMakeLists.txt b/ros2_ws/src/rcdt_detection/CMakeLists.txt index 60c18c0..6545911 100644 --- a/ros2_ws/src/rcdt_detection/CMakeLists.txt +++ b/ros2_ws/src/rcdt_detection/CMakeLists.txt @@ -3,29 +3,32 @@ # SPDX-License-Identifier: Apache-2.0 cmake_minimum_required(VERSION 3.5) - project(rcdt_detection) -find_package(rclpy REQUIRED) +# CMake dependencies: find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) -find_package(rcdt_utilities REQUIRED) -# Install project files: -install( - DIRECTORY launch - DESTINATION share/${PROJECT_NAME} -) +# Other dependencies: +find_package(rclpy REQUIRED) +find_package(rcdt_utilities REQUIRED) -# Install python executables: +# Python executables: install( - DIRECTORY nodes/ + DIRECTORY src_py/ DESTINATION lib/${PROJECT_NAME} ) -# Install python package: +# Python package: ament_python_install_package(${PROJECT_NAME}) +# Shared folders: +install( + DIRECTORY launch + DESTINATION share/${PROJECT_NAME} +) + +# Default test: if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/ros2_ws/src/rcdt_detection/nodes/get_mask_properties.py b/ros2_ws/src/rcdt_detection/src_py/get_mask_properties.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/get_mask_properties.py rename to ros2_ws/src/rcdt_detection/src_py/get_mask_properties.py diff --git a/ros2_ws/src/rcdt_detection/nodes/get_rgbd_from_topic_node.py b/ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic_node.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/get_rgbd_from_topic_node.py rename to ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic_node.py diff --git a/ros2_ws/src/rcdt_detection/nodes/pose_from_pixel_node.py b/ros2_ws/src/rcdt_detection/src_py/pose_from_pixel_node.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/pose_from_pixel_node.py rename to ros2_ws/src/rcdt_detection/src_py/pose_from_pixel_node.py diff --git a/ros2_ws/src/rcdt_detection/nodes/publish_image_node.py b/ros2_ws/src/rcdt_detection/src_py/publish_image_node.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/publish_image_node.py rename to ros2_ws/src/rcdt_detection/src_py/publish_image_node.py diff --git a/ros2_ws/src/rcdt_detection/nodes/publish_masks_node.py b/ros2_ws/src/rcdt_detection/src_py/publish_masks_node.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/publish_masks_node.py rename to ros2_ws/src/rcdt_detection/src_py/publish_masks_node.py diff --git a/ros2_ws/src/rcdt_detection/nodes/segment_image_node.py b/ros2_ws/src/rcdt_detection/src_py/segment_image_node.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/segment_image_node.py rename to ros2_ws/src/rcdt_detection/src_py/segment_image_node.py diff --git a/ros2_ws/src/rcdt_detection/nodes/select_image_from_list_node.py b/ros2_ws/src/rcdt_detection/src_py/select_image_from_list_node.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/select_image_from_list_node.py rename to ros2_ws/src/rcdt_detection/src_py/select_image_from_list_node.py diff --git a/ros2_ws/src/rcdt_detection/nodes/select_pick_location_node.py b/ros2_ws/src/rcdt_detection/src_py/select_pick_location_node.py similarity index 100% rename from ros2_ws/src/rcdt_detection/nodes/select_pick_location_node.py rename to ros2_ws/src/rcdt_detection/src_py/select_pick_location_node.py diff --git a/ros2_ws/src/rcdt_franka/CMakeLists.txt b/ros2_ws/src/rcdt_franka/CMakeLists.txt index fa23224..b58335c 100644 --- a/ros2_ws/src/rcdt_franka/CMakeLists.txt +++ b/ros2_ws/src/rcdt_franka/CMakeLists.txt @@ -3,24 +3,25 @@ # SPDX-License-Identifier: Apache-2.0 cmake_minimum_required(VERSION 3.5) - project(rcdt_franka) +# CMake dependencies: find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) -# Install project files: +# Python executables: install( - DIRECTORY launch config urdf - DESTINATION share/${PROJECT_NAME} + DIRECTORY src_py/ + DESTINATION lib/${PROJECT_NAME} ) -# Install python executables: +# Shared folders: install( - DIRECTORY nodes/ - DESTINATION lib/${PROJECT_NAME} + DIRECTORY launch config urdf + DESTINATION share/${PROJECT_NAME} ) +# Default test: if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/ros2_ws/src/rcdt_franka/nodes/close_gripper_node.py b/ros2_ws/src/rcdt_franka/src_py/close_gripper_node.py similarity index 100% rename from ros2_ws/src/rcdt_franka/nodes/close_gripper_node.py rename to ros2_ws/src/rcdt_franka/src_py/close_gripper_node.py diff --git a/ros2_ws/src/rcdt_franka/nodes/franka_gripper_simulation_node.py b/ros2_ws/src/rcdt_franka/src_py/franka_gripper_simulation_node.py similarity index 100% rename from ros2_ws/src/rcdt_franka/nodes/franka_gripper_simulation_node.py rename to ros2_ws/src/rcdt_franka/src_py/franka_gripper_simulation_node.py diff --git a/ros2_ws/src/rcdt_franka/nodes/joy_to_gripper_node.py b/ros2_ws/src/rcdt_franka/src_py/joy_to_gripper_node.py similarity index 100% rename from ros2_ws/src/rcdt_franka/nodes/joy_to_gripper_node.py rename to ros2_ws/src/rcdt_franka/src_py/joy_to_gripper_node.py diff --git a/ros2_ws/src/rcdt_franka/nodes/open_gripper_node.py b/ros2_ws/src/rcdt_franka/src_py/open_gripper_node.py similarity index 100% rename from ros2_ws/src/rcdt_franka/nodes/open_gripper_node.py rename to ros2_ws/src/rcdt_franka/src_py/open_gripper_node.py diff --git a/ros2_ws/src/rcdt_franka/nodes/settings_setter_node.py b/ros2_ws/src/rcdt_franka/src_py/settings_setter_node.py similarity index 100% rename from ros2_ws/src/rcdt_franka/nodes/settings_setter_node.py rename to ros2_ws/src/rcdt_franka/src_py/settings_setter_node.py diff --git a/ros2_ws/src/rcdt_gz_worlds/CMakeLists.txt b/ros2_ws/src/rcdt_gz_worlds/CMakeLists.txt index 6894902..37dc8a2 100644 --- a/ros2_ws/src/rcdt_gz_worlds/CMakeLists.txt +++ b/ros2_ws/src/rcdt_gz_worlds/CMakeLists.txt @@ -3,17 +3,18 @@ # SPDX-License-Identifier: Apache-2.0 cmake_minimum_required(VERSION 3.5) - project(rcdt_gz_worlds) +# CMake dependencies: find_package(ament_cmake REQUIRED) -# Install project files: +# Shared folders: install( DIRECTORY launch worlds DESTINATION share/${PROJECT_NAME} ) +# Default test: if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/ros2_ws/src/rcdt_mobile_manipulator/CMakeLists.txt b/ros2_ws/src/rcdt_mobile_manipulator/CMakeLists.txt index 5ab67fa..3934ad2 100644 --- a/ros2_ws/src/rcdt_mobile_manipulator/CMakeLists.txt +++ b/ros2_ws/src/rcdt_mobile_manipulator/CMakeLists.txt @@ -3,24 +3,25 @@ # SPDX-License-Identifier: Apache-2.0 cmake_minimum_required(VERSION 3.5) - project(rcdt_mobile_manipulator) +# CMake dependencies: find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) -# Install project files: +# Python executables: install( - DIRECTORY launch config urdf - DESTINATION share/${PROJECT_NAME} + DIRECTORY src_py/ + DESTINATION lib/${PROJECT_NAME} ) -# Install python executables: +# Shared folders: install( - DIRECTORY nodes/ - DESTINATION lib/${PROJECT_NAME} + DIRECTORY launch config urdf + DESTINATION share/${PROJECT_NAME} ) +# Default test: if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/ros2_ws/src/rcdt_mobile_manipulator/nodes/joy_topic_manager_node.py b/ros2_ws/src/rcdt_mobile_manipulator/src_py/joy_topic_manager_node.py similarity index 100% rename from ros2_ws/src/rcdt_mobile_manipulator/nodes/joy_topic_manager_node.py rename to ros2_ws/src/rcdt_mobile_manipulator/src_py/joy_topic_manager_node.py diff --git a/ros2_ws/src/rcdt_panther/CMakeLists.txt b/ros2_ws/src/rcdt_panther/CMakeLists.txt index cfcae8a..58dc357 100644 --- a/ros2_ws/src/rcdt_panther/CMakeLists.txt +++ b/ros2_ws/src/rcdt_panther/CMakeLists.txt @@ -3,18 +3,19 @@ # SPDX-License-Identifier: Apache-2.0 cmake_minimum_required(VERSION 3.5) - project(rcdt_panther) +# CMake dependencies: find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) -# Install project files: +# Shared folders: install( DIRECTORY launch config DESTINATION share/${PROJECT_NAME} ) +# Default test: if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/ros2_ws/src/rcdt_sensors/CMakeLists.txt b/ros2_ws/src/rcdt_sensors/CMakeLists.txt index f97fd9c..f71f9ec 100644 --- a/ros2_ws/src/rcdt_sensors/CMakeLists.txt +++ b/ros2_ws/src/rcdt_sensors/CMakeLists.txt @@ -3,26 +3,28 @@ # SPDX-License-Identifier: Apache-2.0 cmake_minimum_required(VERSION 3.5) - project(rcdt_sensors) +# CMake dependencies: find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) + +# Other dependencies: find_package(rclpy REQUIRED) find_package(sensor_msgs REQUIRED) find_package(realsense2_camera_msgs REQUIRED) find_package(rcdt_utilities REQUIRED) -# Install project files: +# Python executables: install( - DIRECTORY urdf - DESTINATION share/${PROJECT_NAME} + DIRECTORY src_py/ + DESTINATION lib/${PROJECT_NAME} ) -# Install python executables: +# Shared folders: install( - DIRECTORY nodes/ - DESTINATION lib/${PROJECT_NAME} + DIRECTORY urdf + DESTINATION share/${PROJECT_NAME} ) if(BUILD_TESTING) diff --git a/ros2_ws/src/rcdt_sensors/nodes/combine_camera_topics_node.py b/ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics_node.py similarity index 100% rename from ros2_ws/src/rcdt_sensors/nodes/combine_camera_topics_node.py rename to ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics_node.py diff --git a/ros2_ws/src/rcdt_sensors/nodes/convert_32FC1_to_16UC1_node.py b/ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1_node.py similarity index 100% rename from ros2_ws/src/rcdt_sensors/nodes/convert_32FC1_to_16UC1_node.py rename to ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1_node.py diff --git a/ros2_ws/src/rcdt_utilities/CMakeLists.txt b/ros2_ws/src/rcdt_utilities/CMakeLists.txt index ffa5f49..2b303ab 100644 --- a/ros2_ws/src/rcdt_utilities/CMakeLists.txt +++ b/ros2_ws/src/rcdt_utilities/CMakeLists.txt @@ -3,42 +3,43 @@ # SPDX-License-Identifier: Apache-2.0 cmake_minimum_required(VERSION 3.5) - project(rcdt_utilities) +# CMake dependencies: find_package(ament_cmake REQUIRED) find_package(ament_cmake_python REQUIRED) -find_package(rclcpp REQUIRED) +# Other dependencies: +find_package(rclcpp REQUIRED) find_package(std_srvs REQUIRED) find_package(rcdt_utilities_msgs REQUIRED) - find_package(rviz_visual_tools REQUIRED) find_package(tf2_eigen REQUIRED) -# Install project files: +# C++ executables: +add_executable(rviz_controller_node src/rviz_controller_node.cpp) +ament_target_dependencies(rviz_controller_node rclcpp std_srvs rcdt_utilities_msgs rviz_visual_tools tf2_eigen) install( - DIRECTORY launch rviz - DESTINATION share/${PROJECT_NAME} + TARGETS rviz_controller_node + DESTINATION lib/${PROJECT_NAME} ) -# Install python executables: +# Python executables: install( - DIRECTORY nodes/ + DIRECTORY src_py/ DESTINATION lib/${PROJECT_NAME} ) -# Install python package +# Python package: ament_python_install_package(${PROJECT_NAME}) -# Install cpp executables: -add_executable(rviz_controller_node src/rviz_controller_node.cpp) -ament_target_dependencies(rviz_controller_node rclcpp std_srvs rcdt_utilities_msgs rviz_visual_tools tf2_eigen) +# Shared folders: install( - TARGETS rviz_controller_node - DESTINATION lib/${PROJECT_NAME} + DIRECTORY launch rviz + DESTINATION share/${PROJECT_NAME} ) +# Default test: if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() diff --git a/ros2_ws/src/rcdt_utilities/nodes/joy_to_twist_node.py b/ros2_ws/src/rcdt_utilities/src_py/joy_to_twist_node.py similarity index 100% rename from ros2_ws/src/rcdt_utilities/nodes/joy_to_twist_node.py rename to ros2_ws/src/rcdt_utilities/src_py/joy_to_twist_node.py diff --git a/ros2_ws/src/rcdt_utilities/nodes/manipulate_pose_node.py b/ros2_ws/src/rcdt_utilities/src_py/manipulate_pose_node.py similarity index 100% rename from ros2_ws/src/rcdt_utilities/nodes/manipulate_pose_node.py rename to ros2_ws/src/rcdt_utilities/src_py/manipulate_pose_node.py diff --git a/ros2_ws/src/rcdt_utilities/nodes/moveit_controller_node.py b/ros2_ws/src/rcdt_utilities/src_py/moveit_controller_node.py similarity index 100% rename from ros2_ws/src/rcdt_utilities/nodes/moveit_controller_node.py rename to ros2_ws/src/rcdt_utilities/src_py/moveit_controller_node.py From de3f3158c4572b00b7304c6d7b2d38a724c9c629 Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 3 Jan 2025 14:12:55 +0100 Subject: [PATCH 3/6] Apply package.xml conventions from docs. Signed-off-by: Jelmer de Wolde --- ros2_ws/src/rcdt_detection_msgs/package.xml | 5 ++--- ros2_ws/src/rcdt_utilities_msgs/package.xml | 2 -- 2 files changed, 2 insertions(+), 5 deletions(-) diff --git a/ros2_ws/src/rcdt_detection_msgs/package.xml b/ros2_ws/src/rcdt_detection_msgs/package.xml index 89a3086..b2a9921 100644 --- a/ros2_ws/src/rcdt_detection_msgs/package.xml +++ b/ros2_ws/src/rcdt_detection_msgs/package.xml @@ -15,12 +15,11 @@ SPDX-License-Identifier: Apache-2.0 Apache 2.0 ament_cmake - - geometry_msgs rosidl_default_generators - rosidl_default_runtime rosidl_interface_packages + geometry_msgs + ament_lint_auto ament_lint_common diff --git a/ros2_ws/src/rcdt_utilities_msgs/package.xml b/ros2_ws/src/rcdt_utilities_msgs/package.xml index 918832d..bfdcf8b 100644 --- a/ros2_ws/src/rcdt_utilities_msgs/package.xml +++ b/ros2_ws/src/rcdt_utilities_msgs/package.xml @@ -15,8 +15,6 @@ SPDX-License-Identifier: Apache-2.0 Apache 2.0 ament_cmake - ament_cmake_python - rosidl_default_generators rosidl_interface_packages From 5e7f128f9fe6a619a8302f0d3c6296dbbb9fa0f3 Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 3 Jan 2025 14:22:56 +0100 Subject: [PATCH 4/6] Remove _node in python executables names. Signed-off-by: Jelmer de Wolde --- .../src/rcdt_detection/launch/realsense.launch.py | 4 ++-- ...gbd_from_topic_node.py => get_rgbd_from_topic.py} | 0 .../{pose_from_pixel_node.py => pose_from_pixel.py} | 0 .../{publish_image_node.py => publish_image.py} | 0 .../{publish_masks_node.py => publish_masks.py} | 0 .../{segment_image_node.py => segment_image.py} | 0 ...e_from_list_node.py => select_image_from_list.py} | 0 ...pick_location_node.py => select_pick_location.py} | 0 ros2_ws/src/rcdt_franka/launch/controllers.launch.py | 2 +- ros2_ws/src/rcdt_franka/launch/franka.launch.py | 12 ++++++------ ros2_ws/src/rcdt_franka/launch/robot.launch.py | 2 +- .../{close_gripper_node.py => close_gripper.py} | 0 ...mulation_node.py => franka_gripper_simulation.py} | 0 .../{joy_to_gripper_node.py => joy_to_gripper.py} | 0 .../src_py/{open_gripper_node.py => open_gripper.py} | 0 .../{settings_setter_node.py => settings_setter.py} | 0 .../launch/mobile_manipulator.launch.py | 8 ++++---- ...oy_topic_manager_node.py => joy_topic_manager.py} | 0 ros2_ws/src/rcdt_panther/launch/panther.launch.py | 2 +- ...amera_topics_node.py => combine_camera_topics.py} | 0 ...C1_to_16UC1_node.py => convert_32FC1_to_16UC1.py} | 0 ros2_ws/src/rcdt_utilities/launch/moveit.launch.py | 2 +- .../src_py/{joy_to_twist_node.py => joy_to_twist.py} | 0 .../{manipulate_pose_node.py => manipulate_pose.py} | 0 ...oveit_controller_node.py => moveit_controller.py} | 0 25 files changed, 16 insertions(+), 16 deletions(-) rename ros2_ws/src/rcdt_detection/src_py/{get_rgbd_from_topic_node.py => get_rgbd_from_topic.py} (100%) rename ros2_ws/src/rcdt_detection/src_py/{pose_from_pixel_node.py => pose_from_pixel.py} (100%) rename ros2_ws/src/rcdt_detection/src_py/{publish_image_node.py => publish_image.py} (100%) rename ros2_ws/src/rcdt_detection/src_py/{publish_masks_node.py => publish_masks.py} (100%) rename ros2_ws/src/rcdt_detection/src_py/{segment_image_node.py => segment_image.py} (100%) rename ros2_ws/src/rcdt_detection/src_py/{select_image_from_list_node.py => select_image_from_list.py} (100%) rename ros2_ws/src/rcdt_detection/src_py/{select_pick_location_node.py => select_pick_location.py} (100%) rename ros2_ws/src/rcdt_franka/src_py/{close_gripper_node.py => close_gripper.py} (100%) rename ros2_ws/src/rcdt_franka/src_py/{franka_gripper_simulation_node.py => franka_gripper_simulation.py} (100%) rename ros2_ws/src/rcdt_franka/src_py/{joy_to_gripper_node.py => joy_to_gripper.py} (100%) rename ros2_ws/src/rcdt_franka/src_py/{open_gripper_node.py => open_gripper.py} (100%) rename ros2_ws/src/rcdt_franka/src_py/{settings_setter_node.py => settings_setter.py} (100%) rename ros2_ws/src/rcdt_mobile_manipulator/src_py/{joy_topic_manager_node.py => joy_topic_manager.py} (100%) rename ros2_ws/src/rcdt_sensors/src_py/{combine_camera_topics_node.py => combine_camera_topics.py} (100%) rename ros2_ws/src/rcdt_sensors/src_py/{convert_32FC1_to_16UC1_node.py => convert_32FC1_to_16UC1.py} (100%) rename ros2_ws/src/rcdt_utilities/src_py/{joy_to_twist_node.py => joy_to_twist.py} (100%) rename ros2_ws/src/rcdt_utilities/src_py/{manipulate_pose_node.py => manipulate_pose.py} (100%) rename ros2_ws/src/rcdt_utilities/src_py/{moveit_controller_node.py => moveit_controller.py} (100%) diff --git a/ros2_ws/src/rcdt_detection/launch/realsense.launch.py b/ros2_ws/src/rcdt_detection/launch/realsense.launch.py index f479236..f7b726e 100644 --- a/ros2_ws/src/rcdt_detection/launch/realsense.launch.py +++ b/ros2_ws/src/rcdt_detection/launch/realsense.launch.py @@ -17,11 +17,11 @@ def launch_setup(context: LaunchContext) -> list: if use_sim: convert_32FC1_to_16UC1_node = Node( # noqa: N806 package="rcdt_sensors", - executable="convert_32FC1_to_16UC1_node.py", + executable="convert_32FC1_to_16UC1.py", ) combine_camera_topics_node = Node( package="rcdt_sensors", - executable="combine_camera_topics_node.py", + executable="combine_camera_topics.py", ) realsense = LaunchDescription( [ diff --git a/ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic_node.py b/ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic.py similarity index 100% rename from ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic_node.py rename to ros2_ws/src/rcdt_detection/src_py/get_rgbd_from_topic.py diff --git a/ros2_ws/src/rcdt_detection/src_py/pose_from_pixel_node.py b/ros2_ws/src/rcdt_detection/src_py/pose_from_pixel.py similarity index 100% rename from ros2_ws/src/rcdt_detection/src_py/pose_from_pixel_node.py rename to ros2_ws/src/rcdt_detection/src_py/pose_from_pixel.py diff --git a/ros2_ws/src/rcdt_detection/src_py/publish_image_node.py b/ros2_ws/src/rcdt_detection/src_py/publish_image.py similarity index 100% rename from ros2_ws/src/rcdt_detection/src_py/publish_image_node.py rename to ros2_ws/src/rcdt_detection/src_py/publish_image.py diff --git a/ros2_ws/src/rcdt_detection/src_py/publish_masks_node.py b/ros2_ws/src/rcdt_detection/src_py/publish_masks.py similarity index 100% rename from ros2_ws/src/rcdt_detection/src_py/publish_masks_node.py rename to ros2_ws/src/rcdt_detection/src_py/publish_masks.py diff --git a/ros2_ws/src/rcdt_detection/src_py/segment_image_node.py b/ros2_ws/src/rcdt_detection/src_py/segment_image.py similarity index 100% rename from ros2_ws/src/rcdt_detection/src_py/segment_image_node.py rename to ros2_ws/src/rcdt_detection/src_py/segment_image.py diff --git a/ros2_ws/src/rcdt_detection/src_py/select_image_from_list_node.py b/ros2_ws/src/rcdt_detection/src_py/select_image_from_list.py similarity index 100% rename from ros2_ws/src/rcdt_detection/src_py/select_image_from_list_node.py rename to ros2_ws/src/rcdt_detection/src_py/select_image_from_list.py diff --git a/ros2_ws/src/rcdt_detection/src_py/select_pick_location_node.py b/ros2_ws/src/rcdt_detection/src_py/select_pick_location.py similarity index 100% rename from ros2_ws/src/rcdt_detection/src_py/select_pick_location_node.py rename to ros2_ws/src/rcdt_detection/src_py/select_pick_location.py diff --git a/ros2_ws/src/rcdt_franka/launch/controllers.launch.py b/ros2_ws/src/rcdt_franka/launch/controllers.launch.py index 65eb774..2796ff4 100644 --- a/ros2_ws/src/rcdt_franka/launch/controllers.launch.py +++ b/ros2_ws/src/rcdt_franka/launch/controllers.launch.py @@ -37,7 +37,7 @@ def launch_setup(context: LaunchContext) -> None: if simulation: fr3_gripper = Node( package="rcdt_franka", - executable="franka_gripper_simulation_node.py", + executable="franka_gripper_simulation.py", output="screen", ) else: diff --git a/ros2_ws/src/rcdt_franka/launch/franka.launch.py b/ros2_ws/src/rcdt_franka/launch/franka.launch.py index fecbe8a..79bdb9b 100644 --- a/ros2_ws/src/rcdt_franka/launch/franka.launch.py +++ b/ros2_ws/src/rcdt_franka/launch/franka.launch.py @@ -113,12 +113,12 @@ def launch_setup(context: LaunchContext) -> None: joy_topic_manager = Node( package="rcdt_mobile_manipulator", - executable="joy_topic_manager_node.py", + executable="joy_topic_manager.py", ) joy_to_twist_franka = Node( package="rcdt_utilities", - executable="joy_to_twist_node.py", + executable="joy_to_twist.py", namespace="franka", parameters=[ {"sub_topic": "/franka/joy"}, @@ -130,19 +130,19 @@ def launch_setup(context: LaunchContext) -> None: joy_to_gripper = Node( package="rcdt_franka", - executable="joy_to_gripper_node.py", + executable="joy_to_gripper.py", ) open_gripper = Node( package="rcdt_franka", - executable="open_gripper_node.py", + executable="open_gripper.py", ) close_gripper = Node( package="rcdt_franka", - executable="close_gripper_node.py", + executable="close_gripper.py", ) manipulate_pose = Node( - package="rcdt_utilities", executable="manipulate_pose_node.py" + package="rcdt_utilities", executable="manipulate_pose.py" ) skip = LaunchDescriptionEntity() diff --git a/ros2_ws/src/rcdt_franka/launch/robot.launch.py b/ros2_ws/src/rcdt_franka/launch/robot.launch.py index c925839..926cb68 100644 --- a/ros2_ws/src/rcdt_franka/launch/robot.launch.py +++ b/ros2_ws/src/rcdt_franka/launch/robot.launch.py @@ -27,7 +27,7 @@ settings_setter = Node( package="rcdt_franka", - executable="settings_setter_node.py", + executable="settings_setter.py", ) joint_state_publisher = Node( diff --git a/ros2_ws/src/rcdt_franka/src_py/close_gripper_node.py b/ros2_ws/src/rcdt_franka/src_py/close_gripper.py similarity index 100% rename from ros2_ws/src/rcdt_franka/src_py/close_gripper_node.py rename to ros2_ws/src/rcdt_franka/src_py/close_gripper.py diff --git a/ros2_ws/src/rcdt_franka/src_py/franka_gripper_simulation_node.py b/ros2_ws/src/rcdt_franka/src_py/franka_gripper_simulation.py similarity index 100% rename from ros2_ws/src/rcdt_franka/src_py/franka_gripper_simulation_node.py rename to ros2_ws/src/rcdt_franka/src_py/franka_gripper_simulation.py diff --git a/ros2_ws/src/rcdt_franka/src_py/joy_to_gripper_node.py b/ros2_ws/src/rcdt_franka/src_py/joy_to_gripper.py similarity index 100% rename from ros2_ws/src/rcdt_franka/src_py/joy_to_gripper_node.py rename to ros2_ws/src/rcdt_franka/src_py/joy_to_gripper.py diff --git a/ros2_ws/src/rcdt_franka/src_py/open_gripper_node.py b/ros2_ws/src/rcdt_franka/src_py/open_gripper.py similarity index 100% rename from ros2_ws/src/rcdt_franka/src_py/open_gripper_node.py rename to ros2_ws/src/rcdt_franka/src_py/open_gripper.py diff --git a/ros2_ws/src/rcdt_franka/src_py/settings_setter_node.py b/ros2_ws/src/rcdt_franka/src_py/settings_setter.py similarity index 100% rename from ros2_ws/src/rcdt_franka/src_py/settings_setter_node.py rename to ros2_ws/src/rcdt_franka/src_py/settings_setter.py diff --git a/ros2_ws/src/rcdt_mobile_manipulator/launch/mobile_manipulator.launch.py b/ros2_ws/src/rcdt_mobile_manipulator/launch/mobile_manipulator.launch.py index 3f7f589..d51927c 100644 --- a/ros2_ws/src/rcdt_mobile_manipulator/launch/mobile_manipulator.launch.py +++ b/ros2_ws/src/rcdt_mobile_manipulator/launch/mobile_manipulator.launch.py @@ -89,12 +89,12 @@ def launch_setup(context: LaunchContext) -> None: joy_topic_manager = Node( package="rcdt_mobile_manipulator", - executable="joy_topic_manager_node.py", + executable="joy_topic_manager.py", ) joy_to_twist_franka = Node( package="rcdt_utilities", - executable="joy_to_twist_node.py", + executable="joy_to_twist.py", namespace="franka", parameters=[ {"sub_topic": "/franka/joy"}, @@ -106,7 +106,7 @@ def launch_setup(context: LaunchContext) -> None: joy_to_twist_panther = Node( package="rcdt_utilities", - executable="joy_to_twist_node.py", + executable="joy_to_twist.py", namespace="panther", parameters=[ {"sub_topic": "/panther/joy"}, @@ -117,7 +117,7 @@ def launch_setup(context: LaunchContext) -> None: joy_to_gripper = Node( package="rcdt_franka", - executable="joy_to_gripper_node.py", + executable="joy_to_gripper.py", parameters=[{"sub_topic": "/franka/joy"}], ) diff --git a/ros2_ws/src/rcdt_mobile_manipulator/src_py/joy_topic_manager_node.py b/ros2_ws/src/rcdt_mobile_manipulator/src_py/joy_topic_manager.py similarity index 100% rename from ros2_ws/src/rcdt_mobile_manipulator/src_py/joy_topic_manager_node.py rename to ros2_ws/src/rcdt_mobile_manipulator/src_py/joy_topic_manager.py diff --git a/ros2_ws/src/rcdt_panther/launch/panther.launch.py b/ros2_ws/src/rcdt_panther/launch/panther.launch.py index 92516a6..8785071 100644 --- a/ros2_ws/src/rcdt_panther/launch/panther.launch.py +++ b/ros2_ws/src/rcdt_panther/launch/panther.launch.py @@ -63,7 +63,7 @@ def launch_setup(context: LaunchContext) -> None: joy_to_twist_node = Node( package="rcdt_utilities", - executable="joy_to_twist_node.py", + executable="joy_to_twist.py", parameters=[ {"pub_topic": "/diff_drive_controller/cmd_vel"}, {"config_pkg": "rcdt_panther"}, diff --git a/ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics_node.py b/ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics.py similarity index 100% rename from ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics_node.py rename to ros2_ws/src/rcdt_sensors/src_py/combine_camera_topics.py diff --git a/ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1_node.py b/ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1.py similarity index 100% rename from ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1_node.py rename to ros2_ws/src/rcdt_sensors/src_py/convert_32FC1_to_16UC1.py diff --git a/ros2_ws/src/rcdt_utilities/launch/moveit.launch.py b/ros2_ws/src/rcdt_utilities/launch/moveit.launch.py index 2004b19..be49ae1 100644 --- a/ros2_ws/src/rcdt_utilities/launch/moveit.launch.py +++ b/ros2_ws/src/rcdt_utilities/launch/moveit.launch.py @@ -35,7 +35,7 @@ def launch_setup(context: LaunchContext) -> None: # Moveit as node: moveit_node = Node( package="rcdt_utilities", - executable="moveit_controller_node.py", + executable="moveit_controller.py", parameters=[moveit_config, {"use_sim_time": use_sim}], ) diff --git a/ros2_ws/src/rcdt_utilities/src_py/joy_to_twist_node.py b/ros2_ws/src/rcdt_utilities/src_py/joy_to_twist.py similarity index 100% rename from ros2_ws/src/rcdt_utilities/src_py/joy_to_twist_node.py rename to ros2_ws/src/rcdt_utilities/src_py/joy_to_twist.py diff --git a/ros2_ws/src/rcdt_utilities/src_py/manipulate_pose_node.py b/ros2_ws/src/rcdt_utilities/src_py/manipulate_pose.py similarity index 100% rename from ros2_ws/src/rcdt_utilities/src_py/manipulate_pose_node.py rename to ros2_ws/src/rcdt_utilities/src_py/manipulate_pose.py diff --git a/ros2_ws/src/rcdt_utilities/src_py/moveit_controller_node.py b/ros2_ws/src/rcdt_utilities/src_py/moveit_controller.py similarity index 100% rename from ros2_ws/src/rcdt_utilities/src_py/moveit_controller_node.py rename to ros2_ws/src/rcdt_utilities/src_py/moveit_controller.py From df50d2aee87a2969edbd401462f3d0b8538fc24e Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 3 Jan 2025 14:24:14 +0100 Subject: [PATCH 5/6] Fix ruff. Signed-off-by: Jelmer de Wolde --- ros2_ws/src/rcdt_franka/launch/franka.launch.py | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ros2_ws/src/rcdt_franka/launch/franka.launch.py b/ros2_ws/src/rcdt_franka/launch/franka.launch.py index 79bdb9b..3d109b3 100644 --- a/ros2_ws/src/rcdt_franka/launch/franka.launch.py +++ b/ros2_ws/src/rcdt_franka/launch/franka.launch.py @@ -141,9 +141,7 @@ def launch_setup(context: LaunchContext) -> None: executable="close_gripper.py", ) - manipulate_pose = Node( - package="rcdt_utilities", executable="manipulate_pose.py" - ) + manipulate_pose = Node(package="rcdt_utilities", executable="manipulate_pose.py") skip = LaunchDescriptionEntity() return [ From 9633b697fc7f21181d859aa9980fa1a9cbba97dd Mon Sep 17 00:00:00 2001 From: Jelmer de Wolde Date: Fri, 3 Jan 2025 14:30:28 +0100 Subject: [PATCH 6/6] Fix reuse. Signed-off-by: Jelmer de Wolde --- .../ros_msgs_package/CMakeLists.txt | 4 +++ .../example_files/ros_package/CMakeLists.txt | 4 +++ .../example_files/ros_package/package.xml | 7 +++++ docs/content/conventions/ros_package.md | 28 +++++++++++-------- docs/content/conventions/ros_package_msgs.md | 12 ++++++-- 5 files changed, 41 insertions(+), 14 deletions(-) diff --git a/docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt b/docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt index ef700fc..56b4fe5 100644 --- a/docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt +++ b/docs/content/conventions/example_files/ros_msgs_package/CMakeLists.txt @@ -1,3 +1,7 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 + cmake_minimum_required(VERSION 3.5) project(ros_package) diff --git a/docs/content/conventions/example_files/ros_package/CMakeLists.txt b/docs/content/conventions/example_files/ros_package/CMakeLists.txt index 7cb9a11..4519bfc 100644 --- a/docs/content/conventions/example_files/ros_package/CMakeLists.txt +++ b/docs/content/conventions/example_files/ros_package/CMakeLists.txt @@ -1,3 +1,7 @@ +# SPDX-FileCopyrightText: Alliander N. V. +# +# SPDX-License-Identifier: Apache-2.0 + cmake_minimum_required(VERSION 3.5) project(ros_package) diff --git a/docs/content/conventions/example_files/ros_package/package.xml b/docs/content/conventions/example_files/ros_package/package.xml index 8d258a0..108dd54 100644 --- a/docs/content/conventions/example_files/ros_package/package.xml +++ b/docs/content/conventions/example_files/ros_package/package.xml @@ -1,5 +1,12 @@ + + + ros_package 0.1.0 diff --git a/docs/content/conventions/ros_package.md b/docs/content/conventions/ros_package.md index 985af00..d54e0f7 100644 --- a/docs/content/conventions/ros_package.md +++ b/docs/content/conventions/ros_package.md @@ -1,3 +1,9 @@ + + # ros_package conventions ## Folder Structure @@ -43,25 +49,25 @@ This CMakeLists.txt file shows the different parts required to build a ROS packa :linenos: ::: -**1-6**:\ +**5-10**:\ The file always starts with a version definition, the package name and the CMake dependencies when building C++ and/or python files. -**8-10**:\ +**12-14**:\ If the package depends on other packages, these are defined. In this case, the packaged depends on the *vision_msgs* and *geometry_msgs* packages. -**12-18**:\ +**16-22**:\ Building a C++ executable requires 3 steps: defining the executable, linking dependencies (if any) and installing the targets to the lib directory. -**20-24**:\ +**24-28**:\ For Python executables, we can simply install them all at the same time, by providing the directory. -**26-27**:\ +**30-31**:\ If the package contains a Python package, it needs to be installed. -**29-33**\ +**33-37**:\ All shared folders are installed into the share directory. This includes the directory of launch files, but also other possible directories, like `urdf/` or `config/`, if these exist. -**35-41**:\ +**39-45**:\ The file always ends with a default test and the *ament_package()* command. ## package.xml @@ -76,14 +82,14 @@ The package.xml file is related to the CMakeLists.txt file: **1-2**:\ The files starts with default xml definitions. -**3-8**:\ +**10-15**:\ Inside the *package* tag, we start with some general information about the package. -**10-11**:\ +**17-18**:\ Next, we define the build tool dependencies for building C++ and/or Python files. -**13-14**:\ +**20-21**:\ Next, we define other packages where our package depends on. -**16-21**"\ +**23-28**:\ The file ends with the default test dependency and an export definition. diff --git a/docs/content/conventions/ros_package_msgs.md b/docs/content/conventions/ros_package_msgs.md index 218c177..585112c 100644 --- a/docs/content/conventions/ros_package_msgs.md +++ b/docs/content/conventions/ros_package_msgs.md @@ -1,3 +1,9 @@ + + # ros_package_msgs conventions ## Folder Structure @@ -28,13 +34,13 @@ Also the CMakeLists.txt file is very similar. This shows an example where only c :linenos: ::: -**6**:\ +**10**:\ The *rosidl_default_generators* dependency is now required, to generated the custom messages. -**13-18**:\ +**16-22**:\ We use CMake's *GLOB* method to automatically obtain all the srv files. -**20-23**:\ +**24-27**:\ We generate the custom service and link the dependencies (if any). ## package.xml