diff --git a/example_cmake_python/CHANGELOG.rst b/example_cmake_python/CHANGELOG.rst new file mode 100644 index 0000000..c070d64 --- /dev/null +++ b/example_cmake_python/CHANGELOG.rst @@ -0,0 +1,3 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package cmake_generate_parameter_module_example +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/example_cmake_python/CMakeLists.txt b/example_cmake_python/CMakeLists.txt new file mode 100644 index 0000000..d73a42b --- /dev/null +++ b/example_cmake_python/CMakeLists.txt @@ -0,0 +1,15 @@ +cmake_minimum_required(VERSION 3.16) +project(cmake_generate_parameter_module_example) + +find_package(ament_cmake REQUIRED) +find_package(ament_cmake_python REQUIRED) +find_package(generate_parameter_library REQUIRED) + +generate_parameter_module(admittance_parameters + cmake_generate_parameter_module_example/parameters.yaml + cmake_generate_parameter_module_example.custom_validation +) + +ament_python_install_package(${PROJECT_NAME}) + +ament_package() diff --git a/example_cmake_python/README.md b/example_cmake_python/README.md new file mode 100644 index 0000000..596a4f3 --- /dev/null +++ b/example_cmake_python/README.md @@ -0,0 +1,156 @@ +# Example: + +## Build the node + +``` + mkdir -p colcon_ws/src + cd colcon_ws/src + git clone https://github.com/picknikrobotics/generate_parameter_library.git + cd .. + colcon build +``` + +## Run the Python node + +``` +source install/setup.bash +python3 src/generate_parameter_library/example_cmake_python/cmake_generate_parameter_module_example/minimal_publisher.py --ros-args --params-file src/generate_parameter_library/example_python/config/implementation.yaml +``` + +You should see an output like this: +`[INFO] [1656018676.015816509] [admittance_controller]: Initial control frame parameter 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 parameter 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: Trying to set a read-only parameter: command_interfaces.` + +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 array('d', [-10.0, -10.0, -10.0, -10.0, -10.0, -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 + +`python3 src/generate_parameter_library/example_cmake_python/cmake_generate_parameter_module_example/minimal_publisher.py --ros-args --params-file src/generate_parameter_library/example_python/config/missing_required.yaml` + +you will get the error + +``` +Traceback (most recent call last): +[...] +rclpy.exceptions.ParameterUninitializedException: The parameter 'fixed_string_no_default' is not initialized +[ros2run]: Process exited with failure 1 +``` diff --git a/example_cmake_python/cmake_generate_parameter_module_example/__init__.py b/example_cmake_python/cmake_generate_parameter_module_example/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/example_cmake_python/cmake_generate_parameter_module_example/custom_validation.py b/example_cmake_python/cmake_generate_parameter_module_example/custom_validation.py new file mode 100644 index 0000000..03eba7c --- /dev/null +++ b/example_cmake_python/cmake_generate_parameter_module_example/custom_validation.py @@ -0,0 +1,36 @@ +# -*- coding: utf-8 -*- +# Copyright 2023 PickNik Inc. +# +# 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 the PickNik Inc. 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. + + +def no_args_validator(param): + return '' + + +def validate_double_array_custom_func(param, arg1, arg2): + return '' diff --git a/example_cmake_python/cmake_generate_parameter_module_example/minimal_publisher.py b/example_cmake_python/cmake_generate_parameter_module_example/minimal_publisher.py new file mode 100644 index 0000000..58574c9 --- /dev/null +++ b/example_cmake_python/cmake_generate_parameter_module_example/minimal_publisher.py @@ -0,0 +1,75 @@ +# -*- coding: utf-8 -*- +# Copyright 2023 PickNik Inc. +# +# 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 the PickNik Inc. 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. + +import rclpy +import rclpy.node + +from cmake_generate_parameter_module_example.admittance_parameters import ( + admittance_controller, +) + + +class MinimalParam(rclpy.node.Node): + def __init__(self): + super().__init__('admittance_controller') + self.timer = self.create_timer(1, self.timer_callback) + + self.param_listener = admittance_controller.ParamListener(self) + self.params = self.param_listener.get_params() + self.get_logger().info( + "Initial control frame parameter is: '%s'" % self.params.control.frame.id + ) + self.get_logger().info("fixed string is: '%s'" % self.params.fixed_string) + + self.get_logger().info( + "Original joints parameter is: '%s'" % str(self.params.joints) + ) + for d in self.params.fixed_array: + self.get_logger().info("value: '%s'" % str(d)) + + def timer_callback(self): + if self.param_listener.is_old(self.params): + self.param_listener.refresh_dynamic_parameters() + self.params = self.param_listener.get_params() + self.get_logger().info( + "New control frame parameter is: '%s'" % self.params.control.frame.id + ) + self.get_logger().info("fixed string is: '%s'" % self.params.fixed_string) + for d in self.params.fixed_array: + self.get_logger().info("value: '%s'" % str(d)) + + +def main(args=None): + rclpy.init(args=args) + node = MinimalParam() + rclpy.spin(node) + + +if __name__ == '__main__': + main() diff --git a/example_cmake_python/cmake_generate_parameter_module_example/parameters.yaml b/example_cmake_python/cmake_generate_parameter_module_example/parameters.yaml new file mode 100644 index 0000000..d82d40e --- /dev/null +++ b/example_cmake_python/cmake_generate_parameter_module_example/parameters.yaml @@ -0,0 +1,286 @@ +admittance_controller: + scientific_notation_num: { + type: double, + default_value: 0.00000000001, + description: "Test scientific notation", + } + interpolation_mode: { + type: string, + default_value: "spline", + description: "specifies which algorithm to use for interpolation.", + validation: { + one_of<>: [ [ "spline", "linear" ] ], + "custom_validators::no_args_validator": null + } + } + subset_selection: { + type: string_array, + default_value: ["A", "B"], + description: "test subset of validator.", + validation: { + subset_of<>: [ [ "A", "B", "C"] ], + } + } + joints: { + type: string_array, + default_value: ["joint1", "joint2", "joint3"], + description: "specifies which joints will be used by the controller", + } + dof_names: { + type: string_array, + default_value: ["x", "y", "rz"], + description: "specifies which joints will be used by the controller", + } + + pid: + rate: { + type: double, + default_value: 0.005, + description: "update loop period in seconds" + + } + __map_joints: + p: { + type: double, + default_value: 1.0, + description: "proportional gain term", + validation: { + gt_eq<>: [ 0.0001 ], + } + } + i: { + type: double, + default_value: 1.0, + description: "integral gain term" + } + d: { + type: double, + default_value: 1.0, + description: "derivative gain term" + } + + gains: + __map_dof_names: + k: { + type: double, + default_value: 2.0, + description: "general gain" + } + + fixed_string: { + type: string_fixed_25, + default_value: "string_value", + description: "test code generation for fixed sized string", + } + fixed_array: { + type: double_array_fixed_10, + default_value: [1.0, 2.3, 4.0 ,5.4, 3.3], + description: "test code generation for fixed sized array", + } + fixed_string_no_default: { + type: string_fixed_25, + description: "test code generation for fixed sized string with no default", + } + command_interfaces: + { + type: string_array, + description: "specifies which command interfaces to claim", + read_only: true + } + + state_interfaces: + { + type: string_array, + description: "specifies which state interfaces to claim", + read_only: true + } + + chainable_command_interfaces: + { + type: string_array, + description: "specifies which chainable interfaces to claim", + read_only: true + } + + kinematics: + plugin_name: { + type: string, + description: "specifies which kinematics plugin to load" + } + plugin_package: { + type: string, + description: "specifies the package to load the kinematics plugin from" + } + base: { + type: string, + description: "specifies the base link of the robot description used by the kinematics plugin" + } + tip: { + type: string, + description: "specifies the end effector link of the robot description used by the kinematics plugin" + } + alpha: { + type: double, + default_value: 0.0005, + description: "specifies the damping coefficient for the Jacobian pseudo inverse" + } + group_name: { + type: string, + description: "specifies the group name for planning with Moveit" + } + + ft_sensor: + name: { + type: string, + description: "name of the force torque sensor in the robot description" + } + frame: + id: { + type: string, + description: "frame of the force torque sensor" + } + external: { + type: bool, + default_value: false, + description: "specifies if the force torque sensor is contained in the kinematics chain from the base to the tip" + } + filter_coefficient: { + type: double, + default_value: 0.005, + description: "specifies the coefficient for the sensor's exponential filter" + } + + control: + frame: + id: { + type: string, + description: "control frame used for admittance control" + } + external: { + type: bool, + default_value: false, + description: "specifies if the control frame is contained in the kinematics chain from the base to the tip" + } + + fixed_world_frame: # Gravity points down (neg. Z) in this frame (Usually: world or base_link) + frame: + id: { + type: string, + description: "world frame, gravity points down (neg. Z) in this frame" + } + external: { + type: bool, + default_value: false, + description: "specifies if the world frame is contained in the kinematics chain from the base to the tip" + } + + gravity_compensation: + frame: + id: { + type: string, + description: "frame which center of gravity (CoG) is defined in" + } + external: { + type: bool, + default_value: false, + description: "specifies if the center of gravity frame is contained in the kinematics chain from the base to the tip" + } + CoG: # specifies the center of gravity of the end effector + pos: { + type: double_array, + description: "position of the center of gravity (CoG) in its frame", + validation: { + fixed_size<>: 3 + } + } + force: { + type: double, + default_value: .NAN, + description: "weight of the end effector, e.g mass * 9.81" + } + + admittance: + selected_axes: + { + type: bool_array, + description: "specifies if the axes x, y, z, rx, ry, and rz are enabled", + validation: { + fixed_size<>: 6 + } + } + + # Having ".0" at the end is MUST, otherwise there is a loading error + # F = M*a + D*v + S*(x - x_d) + mass: { + type: double_array, + description: "specifies mass values for x, y, z, rx, ry, and rz used in the admittance calculation", + validation: { + fixed_size<>: 6, + element_bounds<>: [ 0.0001, 1000000.0 ] + } + } + + 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 ))", + validation: { + fixed_size<>: 6, + "custom_validators::validate_double_array_custom_func": [ 20.3, 5.0 ], + element_bounds<>: [ 0.1, 10.0 ] + } + } + + stiffness: { + type: double_array, + description: "specifies stiffness values for x, y, z, rx, ry, and rz used in the admittance calculation", + validation: { + element_bounds: [ 0.0001, 100000.0 ] + } + } + + # general settings + enable_parameter_update_without_reactivation: { + type: bool, + default_value: true, + description: "if enabled, read_only parameters will be dynamically updated in the control loop" + } + use_feedforward_commanded_input: { + type: bool, + default_value: false, + description: "if enabled, the velocity commanded to the admittance controller is added to its calculated admittance velocity" + } + lt_eq_fifteen: { + type: int, + default_value: 1, + description: "should be a number less than or equal to 15", + validation: { + lt_eq<>: [ 15 ], + } + } + gt_fifteen: { + type: int, + default_value: 16, + description: "should be a number greater than 15", + validation: { + gt<>: [ 15 ], + } + } + one_number: { + type: int, + default_value: 14540, + read_only: true, + validation: { + bounds<>: [ 1024, 65535 ] + } + } + three_numbers: { + type: int_array, + default_value: [3,4,5], + read_only: true, + } + three_numbers_of_five: { + type: int_array_fixed_5, + default_value: [3,3,3], + read_only: true, + } diff --git a/example_cmake_python/config/implementation.yaml b/example_cmake_python/config/implementation.yaml new file mode 100644 index 0000000..324356c --- /dev/null +++ b/example_cmake_python/config/implementation.yaml @@ -0,0 +1,113 @@ +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" + + 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_cmake_python/config/missing_required.yaml b/example_cmake_python/config/missing_required.yaml new file mode 100644 index 0000000..c29447d --- /dev/null +++ b/example_cmake_python/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_cmake_python/package.xml b/example_cmake_python/package.xml new file mode 100644 index 0000000..917c86f --- /dev/null +++ b/example_cmake_python/package.xml @@ -0,0 +1,22 @@ + + + + cmake_generate_parameter_module_example + 0.3.6 + Example usage of generate_parameter_library for a python module with cmake. + Paul Gesel + BSD-3-Clause + Paul Gesel + + generate_parameter_library + rclpy + + ament_cmake_python + + ament_lint_auto + ament_lint_common + + + ament_cmake + + diff --git a/generate_parameter_library/cmake/generate_parameter_library.cmake b/generate_parameter_library/cmake/generate_parameter_library.cmake index adc70f1..c5f2c10 100644 --- a/generate_parameter_library/cmake/generate_parameter_library.cmake +++ b/generate_parameter_library/cmake/generate_parameter_library.cmake @@ -92,6 +92,52 @@ function(generate_parameter_library LIB_NAME YAML_FILE) install(DIRECTORY ${LIB_INCLUDE_DIR} DESTINATION include/${LIB_NAME}) endfunction() + +function(generate_parameter_module LIB_NAME YAML_FILE) + find_program(generate_parameter_library_python_BIN NAMES "generate_parameter_library_python") + if(NOT generate_parameter_library_python_BIN) + message(FATAL_ERROR "generate_parameter_library_python() variable 'generate_parameter_library_python_BIN' must not be empty") + endif() + + # Optional 3rd parameter for the user defined validation header + if(${ARGC} EQUAL 3) + set(VALIDATE_HEADER_FILENAME ${ARGV2}) + endif() + + # 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}) + file(MAKE_DIRECTORY ${LIB_INCLUDE_DIR}) + + find_package(PythonInterp REQUIRED) + execute_process( + COMMAND "${PYTHON_EXECUTABLE}" -c "import sys;v = sys.version.split()[0];v = v.split('.');print(f'python{v[0]}.{v[1]}')" + OUTPUT_VARIABLE PYTHON_VERSION + OUTPUT_STRIP_TRAILING_WHITESPACE) + + set(PARAM_HEADER_FILE ${CMAKE_INSTALL_PREFIX}/local/lib/${PYTHON_VERSION}/dist-packages/${PROJECT_NAME}/${LIB_NAME}.py) + + + # Generate the module for the python + add_custom_command( + OUTPUT ${PARAM_HEADER_FILE} + COMMAND ${generate_parameter_library_python_BIN} ${PARAM_HEADER_FILE} ${YAML_FILE} ${VALIDATE_HEADER_FILENAME} + DEPENDS ${YAML_FILE} ${VALIDATE_HEADER} + COMMENT + "Running `${generate_parameter_library_python_BIN} ${PARAM_HEADER_FILE} ${YAML_FILE} ${VALIDATE_HEADER_FILENAME}`" + VERBATIM + ) + + # Create the library target + add_library(${LIB_NAME} INTERFACE ${PARAM_HEADER_FILE} ${VALIDATE_HEADER}) + target_include_directories(${LIB_NAME} INTERFACE + $ + $ + ) + +endfunction() + # create custom test function to pass yaml file into test main function(add_rostest_with_parameters_gtest TARGET SOURCES YAML_FILE) add_executable(${TARGET} ${SOURCES})