-
Notifications
You must be signed in to change notification settings - Fork 58
Change header install path #213
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
Changes from all commits
30fc70c
99ffacf
0a64156
80b0ec5
577b895
7b6e66b
d8beefb
6f3bfe7
e821dff
7772d18
bd7c608
cd67e19
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
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 | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I'm just referring to the external example you provided: I did the same but not added it to the target_link_libraries, and it builds fine. (not sure about the implications with CMake and header-only libraries). There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. If you comment out this line and try to build this package in a clean workspace, it should crash and say that it cannot find the parameters headers. I haven't seen your example and the way dependencies are created and linked together, but my guess is that the generated parameter library is linked one way or another to your own library, preventing the crash. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. In other words, linking a target with an interface library comes down to adding the correct headers' path. This is the modern Cmake way of doing things, AFAIK. |
||
) | ||
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() |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -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 | ||
``` |
Uh oh!
There was an error while loading. Please reload this page.