Skip to content

Commit fcb9cca

Browse files
committed
Applied code-review suggestions and fixed includes
1 parent 5715e8f commit fcb9cca

7 files changed

+24
-23
lines changed

CMakeLists.txt

+17-16
Original file line numberDiff line numberDiff line change
@@ -64,19 +64,29 @@ set(CONTROL_FILTERS_INCLUDE_DEPENDS
6464
tf2_ros
6565
)
6666

67+
foreach(Dependency IN ITEMS ${CONTROL_FILTERS_INCLUDE_DEPENDS})
68+
find_package(${Dependency} REQUIRED)
69+
endforeach()
70+
71+
generate_parameter_library(
72+
gravity_compensation_filter_parameters
73+
src/control_filters/gravity_compensation_filter_parameters.yaml
74+
)
75+
6776
add_library(gravity_compensation SHARED
6877
src/control_filters/gravity_compensation.cpp
6978
)
79+
target_compile_features(gravity_compensation PUBLIC cxx_std_17)
7080
target_include_directories(gravity_compensation PUBLIC
7181
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
72-
$<INSTALL_INTERFACE:include>
73-
)
74-
generate_parameter_library(
75-
gravity_compensation_filter_parameters
76-
src/control_filters/gravity_compensation_filter_parameters.yaml
82+
$<INSTALL_INTERFACE:include/control_toolbox>
7783
)
78-
target_link_libraries(gravity_compensation gravity_compensation_filter_parameters)
79-
ament_target_dependencies(gravity_compensation ${CONTROL_FILTERS_INCLUDE_DEPENDS})
84+
85+
target_link_libraries(gravity_compensation PUBLIC gravity_compensation_filter_parameters)
86+
ament_target_dependencies(gravity_compensation PUBLIC ${CONTROL_FILTERS_INCLUDE_DEPENDS})
87+
88+
# Install pluginlib xml
89+
pluginlib_export_plugin_description_file(filters control_filters.xml)
8090

8191
##########
8292
# Testing
@@ -124,18 +134,9 @@ install(TARGETS gravity_compensation gravity_compensation_filter_parameters
124134
RUNTIME DESTINATION bin
125135
)
126136

127-
# Install pluginlib xml
128-
pluginlib_export_plugin_description_file(filters control_filters.xml)
129-
130137
ament_export_targets(export_control_toolbox HAS_LIBRARY_TARGET)
131138
ament_export_dependencies(${THIS_PACKAGE_INCLUDE_DEPENDS} ${CONTROL_FILTERS_INCLUDE_DEPENDS})
132139
ament_export_include_directories(
133140
include
134141
)
135-
ament_export_libraries(
136-
control_toolbox
137-
gravity_compensation
138-
gravity_compensation_filter_parameters
139-
)
140-
141142
ament_package()

README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@ To run it initially over the whole repo you can use:
4545

4646
If you get error that something is missing on your computer, do the following for:
4747

48-
- `clang-format-10`
48+
- `clang-format-14`
4949
```
50-
sudo apt install clang-format-10
50+
sudo apt install clang-format-14
5151
```

include/control_filters/gravity_compensation.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
1+
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.

src/control_filters/gravity_compensation.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
1+
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.

test/control_filters/test_gravity_compensation.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
1+
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.

test/control_filters/test_gravity_compensation.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
1+
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.

test/control_filters/test_load_gravity_compensation.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright (c) 2021, Stogl Robotics Consulting UG (haftungsbeschränkt)
1+
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.

0 commit comments

Comments
 (0)