diff --git a/README.md b/README.md index 5d75d46d..17ece4c3 100644 --- a/README.md +++ b/README.md @@ -63,6 +63,10 @@ target_link_libraries(minimal_node PRIVATE rclcpp::rclcpp turtlesim_parameters ) + +install(TARGETS minimal_node turtlesim_parameters + EXPORT ${PROJECT_NAME}Targets) +ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET) ``` **setup.py** @@ -80,7 +84,7 @@ generate_parameter_module( **src/turtlesim.cpp** ```c++ #include -#include "turtlesim_parameters.hpp" +#include // you can also use the deprecated #include "turtlesim_parameters.hpp" int main(int argc, char * argv[]) { @@ -350,10 +354,46 @@ The generated parameter value for the nested map example can then be accessed wi ### Use generated struct in Cpp The generated header file is named based on the target library name you passed as the first argument to the cmake function. -If you specified it to be `turtlesim_parameters` you can then include the generated code with `#include "turtlesim_parameters.hpp"`. +If you specified it to be `turtlesim_parameters` you can then include the generated code with `#include `. ```c++ -#include "turtlesim_parameters.hpp" +#include ``` + +Note that this header can also be used from another package: +```cmake +cmake_minimum_required(VERSION 3.8) +project(my_other_package) + + +include(GNUInstallDirs) + +# find dependencies +find_package(ament_cmake REQUIRED) +find_package(turtelsim REQUIRED) + +add_library(my_lib src/my_lib.cpp) +target_include_directories(my_lib PUBLIC + $ + $) +target_link_libraries(my_lib PUBLIC turtlesim::turtlesim_parameters) + +############# +## Install ## +############# + +install(DIRECTORY include/${PROJECT_NAME}/ DESTINATION ${CMAKE_INSTALL_INCLUDEDIR}/${PROJECT_NAME}) + +install(TARGETS my_lib + EXPORT ${PROJECT_NAME}Targets + ARCHIVE DESTINATION ${CMAKE_INSTALL_LIBDIR} + LIBRARY DESTINATION ${CMAKE_INSTALL_LIBDIR} + RUNTIME DESTINATION lib/${PROJECT_NAME}) + +ament_export_targets(${PROJECT_NAME}Targets HAS_LIBRARY_TARGET) +ament_export_dependencies(turtlesim) +ament_package() +``` + In your initialization code, create a `ParamListener` which will declare and get the parameters. An exception will be thrown if any validation fails or any required parameters were not set. Then call `get_params` on the listener to get a copy of the `Params` struct. diff --git a/example/include/generate_parameter_library_example/minimal_publisher.hpp b/example/include/generate_parameter_library_example/minimal_publisher.hpp index cacce19d..9a002b7f 100644 --- a/example/include/generate_parameter_library_example/minimal_publisher.hpp +++ b/example/include/generate_parameter_library_example/minimal_publisher.hpp @@ -31,7 +31,7 @@ #include #include -#include +#include namespace admittance_controller { diff --git a/example/src/minimal_publisher.cpp b/example/src/minimal_publisher.cpp index e4021b3d..62cdaa4c 100644 --- a/example/src/minimal_publisher.cpp +++ b/example/src/minimal_publisher.cpp @@ -30,7 +30,7 @@ #include -#include +#include using namespace std::chrono_literals; diff --git a/example/test/descriptor_test_gtest.cpp b/example/test/descriptor_test_gtest.cpp index ee81f0bf..ad349f2f 100644 --- a/example/test/descriptor_test_gtest.cpp +++ b/example/test/descriptor_test_gtest.cpp @@ -29,7 +29,7 @@ // Author: Chance Cardona // -#include "admittance_controller_parameters.hpp" +#include "generate_parameter_library_example/admittance_controller_parameters.hpp" #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" diff --git a/example/test/example_test_gmock.cpp b/example/test/example_test_gmock.cpp index 15b37351..63486c25 100644 --- a/example/test/example_test_gmock.cpp +++ b/example/test/example_test_gmock.cpp @@ -29,7 +29,7 @@ // Author: Denis Štogl // -#include "admittance_controller_parameters.hpp" +#include "generate_parameter_library_example/admittance_controller_parameters.hpp" #include "gmock/gmock.h" #include "rclcpp/rclcpp.hpp" diff --git a/example/test/example_test_gtest.cpp b/example/test/example_test_gtest.cpp index b7593ba1..40e06e14 100644 --- a/example/test/example_test_gtest.cpp +++ b/example/test/example_test_gtest.cpp @@ -29,7 +29,7 @@ // Author: Denis Štogl // -#include "admittance_controller_parameters.hpp" +#include "generate_parameter_library_example/admittance_controller_parameters.hpp" #include "gtest/gtest.h" #include "rclcpp/rclcpp.hpp" diff --git a/example_external/CHANGELOG.rst b/example_external/CHANGELOG.rst new file mode 100644 index 00000000..e69de29b diff --git a/example_external/CMakeLists.txt b/example_external/CMakeLists.txt new file mode 100644 index 00000000..8ab3d38f --- /dev/null +++ b/example_external/CMakeLists.txt @@ -0,0 +1,52 @@ +cmake_minimum_required(VERSION 3.16) +project(generate_parameter_library_example_external) + +if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)") + add_compile_options(-Wall -Wextra -Wpedantic -Wshadow -Wconversion -Wsign-conversion -Wold-style-cast) +endif() + +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) +find_package(rclcpp REQUIRED) +find_package(rclcpp_components REQUIRED) +find_package(rclpy REQUIRED) +find_package(generate_parameter_library_example REQUIRED) + +add_library(minimal_publisher_external SHARED + src/minimal_publisher_external.cpp +) +target_include_directories(minimal_publisher_external PUBLIC + $ + $ +) +target_link_libraries(minimal_publisher_external + PUBLIC + rclcpp::rclcpp + rclcpp_components::component + generate_parameter_library_example::admittance_controller_parameters +) +rclcpp_components_register_node(minimal_publisher_external + PLUGIN "admittance_controller::MinimalPublisher" + EXECUTABLE test_node +) + +install( + DIRECTORY include/ + DESTINATION include/generate_parameter_library_example_external +) + +install(TARGETS minimal_publisher_external + EXPORT export_generate_parameter_library_example_external + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +install( + TARGETS test_node + DESTINATION lib/generate_parameter_library_example_external +) + +ament_export_targets(export_generate_parameter_library_example_external HAS_LIBRARY_TARGET) +ament_export_dependencies(rclcpp rclcpp_components generate_parameter_library_example) +ament_package() diff --git a/example_external/README.md b/example_external/README.md new file mode 100644 index 00000000..09fbb164 --- /dev/null +++ b/example_external/README.md @@ -0,0 +1,162 @@ +# Using parameters defined in another package + +This package is a minimal example demonstrating how the parameters defined in `generate_parameter_library/example` +can be used in a different package (i.e. the current one : `generate_parameter_library/example_external`). + +In particular, check the `CMakeLists.txt` file and the `#include` instructions in the source files. + +## Build the node + +``` + mkdir colcon_ws + mkdir colcon_ws/src + cd colcon_ws/src + git clone https://github.com/picknikrobotics/generate_parameter_library.git + cd .. + colcon build +``` + +## Run the C++ node + +``` +source install/setup.bash +ros2 run generate_parameter_library_example_external test_node --ros-args --params-file src/generate_parameter_library/example_external/config/implementation.yaml +``` + +You should see an output like this: +`[INFO] [1656018676.015816509] [admittance_controller]: Control frame is: 'ee_link'` + +## ROS 2 CLI + +Run the following: + +`ros2 param list` + +You should see: + +``` +/admittance_controller: + admittance.damping_ratio + admittance.mass + admittance.selected_axes + admittance.stiffness + chainable_command_interfaces + command_interfaces + control.frame.external + control.frame.id + enable_parameter_update_without_reactivation + fixed_array + fixed_string + fixed_string_no_default + fixed_world_frame.frame.external + fixed_world_frame.frame.id + ft_sensor.filter_coefficient + ft_sensor.frame.external + ft_sensor.frame.id + ft_sensor.name + gravity_compensation.CoG.force + gravity_compensation.CoG.pos + gravity_compensation.frame.external + gravity_compensation.frame.id + interpolation_mode + joints + kinematics.alpha + kinematics.base + kinematics.group_name + kinematics.plugin_name + kinematics.plugin_package + kinematics.tip + one_number + pid.elbow_joint.d + pid.elbow_joint.i + pid.elbow_joint.p + pid.rate + pid.shoulder_lift_joint.d + pid.shoulder_lift_joint.i + pid.shoulder_lift_joint.p + pid.shoulder_pan_joint.d + pid.shoulder_pan_joint.i + pid.shoulder_pan_joint.p + pid.wrist_1_joint.d + pid.wrist_1_joint.i + pid.wrist_1_joint.p + pid.wrist_2_joint.d + pid.wrist_2_joint.i + pid.wrist_2_joint.p + pid.wrist_3_joint.d + pid.wrist_3_joint.i + pid.wrist_3_joint.p + qos_overrides./parameter_events.publisher.depth + qos_overrides./parameter_events.publisher.durability + qos_overrides./parameter_events.publisher.history + qos_overrides./parameter_events.publisher.reliability + scientific_notation_num + state_interfaces + three_numbers + three_numbers_of_five + use_feedforward_commanded_input + use_sim_time + ``` + +All parameters are automatically declared and callbacks are setup by default. +You can set a parameter by typing: + +`ros2 param set /admittance_controller control.frame.id new_frame` + +You should see: + +`[INFO] [1656019001.515820371] [admittance_controller]: New control frame parameter is: 'new_frame'` + +Congratulations, you updated the parameter! + +If you try to set a parameter that is read only, you will get an error. +Running the following + +`ros2 param set /admittance_controller command_interfaces ["velocity"]` + +will result in the error + +`Setting parameter failed: parameter 'command_interfaces' cannot be set because it is read-only` + +Running the following + +`ros2 param describe /admittance_controller admittance.damping_ratio` + +will show a parameter's description + + ``` + Parameter name: admittance.damping_ratio + Type: double array + Description: specifies damping ratio values for x, y, z, rx, ry, and rz used in the admittance calculation. The values are calculated as damping can be used instead: zeta = D / (2 * sqrt( M * S )) + Constraints: + Min value: 0.1 + Max value: 10.0 +``` + +If you try to set a value out of the specified bounds, + +`ros2 param set /admittance_controller admittance.damping_ratio [-10.0,-10.0,-10.0,-10.0,-10.0,-10.0]` + +you will get the error + +`Setting parameter failed: Value -10.0 in parameter 'admittance.damping_ratio' must be within bounds [0.1, 10.0]` + +If you try to set a vector parameter with the wrong length, + +`ros2 param set /admittance_controller admittance.damping_ratio [1.0,1.0,1.0]` + +you will get the error + +`Setting parameter failed: Length of parameter 'admittance.damping_ratio' is 3 but must be equal to 6` + +If you try to load a yaml file with missing required parameters + +`ros2 run generate_parameter_library_example test_node --ros-args --params-file src/generate_parameter_library/example_external/config/missing_required.yaml` + +you will get the error + +``` +terminate called after throwing an instance of 'rclcpp::exceptions::ParameterUninitializedException' + what(): parameter 'fixed_string_no_default' is not initialized +[ros2run]: Aborted +``` diff --git a/example_external/config/implementation.yaml b/example_external/config/implementation.yaml new file mode 100644 index 00000000..4cd1ba91 --- /dev/null +++ b/example_external/config/implementation.yaml @@ -0,0 +1,117 @@ +admittance_controller: + ros__parameters: + joints: + - shoulder_pan_joint + - shoulder_lift_joint + - elbow_joint + - wrist_1_joint + - wrist_2_joint + - wrist_3_joint + + fixed_string_no_default: + "happy" + + elbow_joint: + x: + weight: 2.0 + + pid: + shoulder_pan_joint: + i: 0.7 + shoulder_lift_joint: + i: 0.5 + elbow_joint: + i: 0.2 + wrist_1_joint: + i: 1.2 + wrist_2_joint: + i: 0.8 + wrist_3_joint: + i: 0.5 + + command_interfaces: + - position + + state_interfaces: + - position + - velocity + + chainable_command_interfaces: + - position + - velocity + + kinematics: + plugin_name: kdl_plugin/KDLKinematics + plugin_package: kinematics_interface_kdl + base: base_link # Assumed to be stationary + tip: ee_link + group_name: ur5e_manipulator + alpha: 0.0005 + + ft_sensor: + name: tcp_fts_sensor + frame: + id: ee_link # ee_link Wrench measurements are in this frame + external: false # force torque frame exists within URDF kinematic chain + filter_coefficient: 0.005 + + control: + frame: + id: ee_link # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector + external: false # control frame exists within URDF kinematic chain + + fixed_world_frame: + frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link) + id: base_link # Admittance calcs (displacement etc) are done in this frame. Usually the tool or end-effector + external: false # control frame exists within URDF kinematic chain + + gravity_compensation: + frame: + id: ee_link + external: false + + CoG: # specifies the center of gravity of the end effector + pos: + - 0.1 # x + - 0.0 # y + - 0.0 # z + force: 23.0 # mass * 9.81 + + admittance: + selected_axes: + - true # x + - true # y + - true # z + - true # rx + - true # ry + - true # rz + + # Having ".0" at the end is MUST, otherwise there is a loading error + # F = M*a + D*v + S*(x - x_d) + mass: + - 3.0 # x + - 3.0 # y + - 3.0 # z + - 0.05 # rx + - 0.05 # ry + - 0.05 # rz + + damping_ratio: # damping can be used instead: zeta = D / (2 * sqrt( M * S )) + - 2.828427 # x + - 2.828427 # y + - 2.828427 # z + - 2.828427 # rx + - 2.828427 # ry + - 2.828427 # rz + + stiffness: + - 50.0 # x + - 50.0 # y + - 50.0 # z + - 1.0 # rx + - 1.0 # ry + - 1.0 # rz + + # general settings + enable_parameter_update_without_reactivation: true + use_feedforward_commanded_input: true diff --git a/example_external/config/missing_required.yaml b/example_external/config/missing_required.yaml new file mode 100644 index 00000000..c29447d7 --- /dev/null +++ b/example_external/config/missing_required.yaml @@ -0,0 +1,9 @@ +admittance_controller: + ros__parameters: + mass: + - -10.0 # x + - -10.0 # y + - 3.0 # z + - 0.05 # rx + - 0.05 # ry + - 0.05 # rz diff --git a/example_external/include/generate_parameter_library_example_external/minimal_publisher_external.hpp b/example_external/include/generate_parameter_library_example_external/minimal_publisher_external.hpp new file mode 100644 index 00000000..cfca521e --- /dev/null +++ b/example_external/include/generate_parameter_library_example_external/minimal_publisher_external.hpp @@ -0,0 +1,52 @@ +// Copyright 2025 Forssea Robotics +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// * Neither the name of Forssea Robotics nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#pragma once + +#include +#include + +#include + +namespace admittance_controller { + +class MinimalPublisher : public rclcpp::Node { + public: + MinimalPublisher(const rclcpp::NodeOptions& options = rclcpp::NodeOptions()); + + private: + void timer_callback(); + + rclcpp::TimerBase::SharedPtr timer_; + std::shared_ptr param_listener_; + admittance_controller::Params params_; +}; + +} // namespace admittance_controller + +RCLCPP_COMPONENTS_REGISTER_NODE(admittance_controller::MinimalPublisher) diff --git a/example_external/package.xml b/example_external/package.xml new file mode 100644 index 00000000..b94f0a59 --- /dev/null +++ b/example_external/package.xml @@ -0,0 +1,25 @@ + + + + generate_parameter_library_example_external + 0.1.0 + Example usage of a parameter header generated in another package. + Paul Gesel + BSD-3-Clause + Auguste Bourgois + + generate_parameter_library_example + rclcpp + rclcpp_components + + ament_cmake + + ament_cmake_core + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/example_external/src/minimal_publisher_external.cpp b/example_external/src/minimal_publisher_external.cpp new file mode 100644 index 00000000..bf2396b2 --- /dev/null +++ b/example_external/src/minimal_publisher_external.cpp @@ -0,0 +1,74 @@ +// Copyright 2025 Forssea Robotics +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// +// * Redistributions in binary form must reproduce the above copyright +// notice, this list of conditions and the following disclaimer in the +// documentation and/or other materials provided with the distribution. +// +// * Neither the name of Forssea Robotics nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE +// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +// POSSIBILITY OF SUCH DAMAGE. + +#include "generate_parameter_library_example_external/minimal_publisher_external.hpp" + +#include + +#include + +using namespace std::chrono_literals; + +namespace admittance_controller { + +MinimalPublisher::MinimalPublisher(const rclcpp::NodeOptions& options) + : Node("admittance_controller", options) { + timer_ = create_wall_timer( + 500ms, std::bind(&MinimalPublisher::timer_callback, this)); + param_listener_ = + std::make_shared(get_node_parameters_interface()); + params_ = param_listener_->get_params(); + + [[maybe_unused]] StackParams s_params = param_listener_->get_stack_params(); + + RCLCPP_INFO(get_logger(), "Initial control frame parameter is: '%s'", + params_.control.frame.id.c_str()); + RCLCPP_INFO(get_logger(), "fixed string is: '%s'", + std::string{params_.fixed_string}.c_str()); + const tcb::span fixed_array = params_.fixed_array; + for (auto d : fixed_array) { + RCLCPP_INFO(get_logger(), "value: '%s'", std::to_string(d).c_str()); + } +} + +void MinimalPublisher::timer_callback() { + if (param_listener_->is_old(params_)) { + param_listener_->refresh_dynamic_parameters(); + params_ = param_listener_->get_params(); + RCLCPP_INFO(get_logger(), "New control frame parameter is: '%s'", + params_.control.frame.id.c_str()); + RCLCPP_INFO(get_logger(), "fixed string is: '%s'", + std::string{params_.fixed_string}.c_str()); + const tcb::span fixed_array = params_.fixed_array; + for (auto d : fixed_array) { + RCLCPP_INFO(get_logger(), "value: '%s'", std::to_string(d).c_str()); + } + } +} + +} // namespace admittance_controller diff --git a/example_python/generate_parameter_module_example/minimal_publisher.py b/example_python/generate_parameter_module_example/minimal_publisher.py index 7eaf59cb..35ae3c24 100644 --- a/example_python/generate_parameter_module_example/minimal_publisher.py +++ b/example_python/generate_parameter_module_example/minimal_publisher.py @@ -36,6 +36,7 @@ class MinimalParam(rclpy.node.Node): + def __init__(self): super().__init__('admittance_controller') self.timer = self.create_timer(1, self.timer_callback) diff --git a/generate_parameter_library/cmake/generate_parameter_library.cmake b/generate_parameter_library/cmake/generate_parameter_library.cmake index ce681d5d..07bf3a29 100644 --- a/generate_parameter_library/cmake/generate_parameter_library.cmake +++ b/generate_parameter_library/cmake/generate_parameter_library.cmake @@ -27,7 +27,7 @@ # POSSIBILITY OF SUCH DAMAGE. -function(generate_parameter_library LIB_NAME YAML_FILE) +macro(generate_parameter_library LIB_NAME YAML_FILE) unset(generate_parameter_library_cpp_BIN CACHE) # Unset the cache variable find_program(generate_parameter_library_cpp_BIN NAMES "generate_parameter_library_cpp") if(NOT generate_parameter_library_cpp_BIN) @@ -35,7 +35,7 @@ function(generate_parameter_library LIB_NAME YAML_FILE) endif() # Make the include directory - set(LIB_INCLUDE_DIR ${CMAKE_CURRENT_BINARY_DIR}/${LIB_NAME}/include/) + set(LIB_INCLUDE_DIR ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_NAME}) file(MAKE_DIRECTORY ${LIB_INCLUDE_DIR}) # Optional 3rd parameter for the user defined validation header @@ -48,18 +48,13 @@ function(generate_parameter_library LIB_NAME YAML_FILE) cmake_path(APPEND VALIDATE_HEADER ${VALIDATE_HEADER_FILENAME}) # Copy the header file into the include directory - add_custom_command( - OUTPUT ${VALIDATE_HEADER} - COMMAND ${CMAKE_COMMAND} -E copy ${IN_VALIDATE_HEADER} ${VALIDATE_HEADER} - DEPENDS ${IN_VALIDATE_HEADER} - COMMENT - "Running `${CMAKE_COMMAND} -E copy ${IN_VALIDATE_HEADER} ${VALIDATE_HEADER}`" - VERBATIM - ) + file(COPY ${IN_VALIDATE_HEADER} DESTINATION ${LIB_INCLUDE_DIR}) + # necessary so that #include can be used in the local package (deprecated) + file(COPY ${IN_VALIDATE_HEADER} DESTINATION ${CMAKE_CURRENT_BINARY_DIR}/include) endif() # Set the yaml file parameter to be relative to the current source dir - set(YAML_FILE ${CMAKE_CURRENT_SOURCE_DIR}/${YAML_FILE}) + set(YAML_FILE_PATH ${CMAKE_CURRENT_SOURCE_DIR}/${YAML_FILE}) # Set the output parameter header file name set(PARAM_HEADER_FILE ${LIB_INCLUDE_DIR}/${LIB_NAME}.hpp) @@ -67,18 +62,32 @@ function(generate_parameter_library LIB_NAME YAML_FILE) # Generate the header for the library add_custom_command( OUTPUT ${PARAM_HEADER_FILE} - COMMAND ${generate_parameter_library_cpp_BIN} ${PARAM_HEADER_FILE} ${YAML_FILE} ${VALIDATE_HEADER_FILENAME} - DEPENDS ${YAML_FILE} ${VALIDATE_HEADER} + COMMAND ${generate_parameter_library_cpp_BIN} ${PARAM_HEADER_FILE} ${YAML_FILE_PATH} ${VALIDATE_HEADER_FILENAME} + DEPENDS ${YAML_FILE_PATH} ${VALIDATE_HEADER} COMMENT - "Running `${generate_parameter_library_cpp_BIN} ${PARAM_HEADER_FILE} ${YAML_FILE} ${VALIDATE_HEADER_FILENAME}`" + "Running `${generate_parameter_library_cpp_BIN} ${PARAM_HEADER_FILE} ${YAML_FILE_PATH} ${VALIDATE_HEADER_FILENAME}`" + VERBATIM + ) + # necessary so that #include can be used in the local package (deprecated) + set(LOCAL_PARAM_HEADER_FILE ${CMAKE_CURRENT_BINARY_DIR}/include/${LIB_NAME}.hpp) + add_custom_command( + OUTPUT ${LOCAL_PARAM_HEADER_FILE} + COMMAND ${CMAKE_COMMAND} -E echo "#pragma message(\"#include \\\"${LIB_NAME}.hpp\\\" is deprecated. \ +Use #include <${PROJECT_NAME}/${LIB_NAME}.hpp> instead.\")" >> ${LOCAL_PARAM_HEADER_FILE} + COMMAND ${CMAKE_COMMAND} -E cat ${LOCAL_PARAM_HEADER_FILE} ${PARAM_HEADER_FILE} > ${LOCAL_PARAM_HEADER_FILE}.tmp + COMMAND ${CMAKE_COMMAND} -E copy ${LOCAL_PARAM_HEADER_FILE}.tmp ${LOCAL_PARAM_HEADER_FILE} + COMMAND ${CMAKE_COMMAND} -E remove ${LOCAL_PARAM_HEADER_FILE}.tmp + DEPENDS ${PARAM_HEADER_FILE} + COMMENT + "Creating deprecated header file ${LOCAL_PARAM_HEADER_FILE}" VERBATIM ) # Create the library target - add_library(${LIB_NAME} INTERFACE ${PARAM_HEADER_FILE} ${VALIDATE_HEADER}) + add_library(${LIB_NAME} INTERFACE ${PARAM_HEADER_FILE} ${VALIDATE_HEADER} ${LOCAL_PARAM_HEADER_FILE}) target_include_directories(${LIB_NAME} INTERFACE - $ - $ + $ + $ ) set_target_properties(${LIB_NAME} PROPERTIES LINKER_LANGUAGE CXX) target_link_libraries(${LIB_NAME} INTERFACE @@ -90,8 +99,9 @@ function(generate_parameter_library LIB_NAME YAML_FILE) tcb_span::tcb_span tl_expected::tl_expected ) - install(DIRECTORY ${LIB_INCLUDE_DIR} DESTINATION include/${LIB_NAME}) -endfunction() + install(DIRECTORY ${LIB_INCLUDE_DIR} DESTINATION include) + ament_export_dependencies(fmt parameter_traits rclcpp rclcpp_lifecycle rsl tcb_span tl_expected) +endmacro() function(generate_parameter_module LIB_NAME YAML_FILE) @@ -108,7 +118,7 @@ function(generate_parameter_module LIB_NAME YAML_FILE) # Set the yaml file parameter to be relative to the current source dir set(YAML_FILE ${CMAKE_CURRENT_SOURCE_DIR}/${YAML_FILE}) - set(LIB_INCLUDE_DIR ${CMAKE_CURRENT_BINARY_DIR}/${LIB_NAME}) + set(LIB_INCLUDE_DIR ${CMAKE_CURRENT_BINARY_DIR}/include/${PROJECT_NAME}) file(MAKE_DIRECTORY ${LIB_INCLUDE_DIR}) find_package(ament_cmake_python) @@ -128,8 +138,8 @@ function(generate_parameter_module LIB_NAME YAML_FILE) # Create the library target add_library(${LIB_NAME} INTERFACE ${PARAM_HEADER_FILE} ${VALIDATE_HEADER}) target_include_directories(${LIB_NAME} INTERFACE - $ - $ + $ + $ ) endfunction()