Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Change header install path #213

Open
wants to merge 11 commits into
base: main
Choose a base branch
from
42 changes: 39 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ generate_parameter_module(
**src/turtlesim.cpp**
```c++
#include <rclcpp/rclcpp.hpp>
#include "turtlesim_parameters.hpp"
#include <turtlesim/turtlesim_parameters.hpp> // you can also use the deprecated #include "turtlesim_parameters.hpp"

int main(int argc, char * argv[])
{
Expand Down Expand Up @@ -348,10 +348,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 <turtlesim/turtlesim_parameters.hpp>`.
```c++
#include "turtlesim_parameters.hpp"
#include <turtlesim/turtlesim_parameters.hpp>
```

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
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
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)
Comment on lines +384 to +390
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The equivalent of these two instructions have to be added in the library, which exports the turtlesim_parameters. Please add this to this section here (it is not part of the minimum CMakeLists snippet)

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The other option is to hide these instructions in the generate_parameter_library cmake command. Which one do you prefer ?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

would there be any drawbacks?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The only effect would be to export the generated header target even if you don't use it outside of your package, which sounds fine to me (same thing with exported dependencies). The main advantage is to group everything under the generate_parameter_library cmake command, which makes it very easy to use.

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

again, I vote for the simplest version to use ;) but I'd understand if someone wants to keep the created artifacts as small as possible

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done. To achieve this, I transformed the function into a macro, so that I don't need to globalize every cmake variable set in the function.

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.
Expand Down
8 changes: 8 additions & 0 deletions example_external/CHANGELOG.rst
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think you don't have to fill it -> this will be filled during the next release.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ok, removed the content of the file. Also corrected the old headers.

Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Changelog for package generate_parameter_library_example_external
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.1.0 (2024-08-07)
------------------
* Example usage of generated header from another package (generate_parameter_library_example)
* Contributors: Auguste Bourgois
52 changes: 52 additions & 0 deletions example_external/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/generate_parameter_library_example_external>
)
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()
155 changes: 155 additions & 0 deletions example_external/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,155 @@
# Example:

## 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 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: 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
```
117 changes: 117 additions & 0 deletions example_external/config/implementation.yaml
Original file line number Diff line number Diff line change
@@ -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
Loading