Skip to content

Commit be213a4

Browse files
committed
Cleanup Boost dependencies
I'm trying to remove the libboost-all-dev from my robot image. I notices there is an exec_depend from `ros2_canopen` to libboost-all-dev. This is not needed for running the application, only for compiling. So I've tried to look at all the boost dependencies and categorized them properly. canopen_402_driver: - uses the headers of boost container and numeric which are part of libboost-all-dev canopen_base_driver: - doesn't depend on boost canopen_core: - boost thread requires linking to libboost-thread and the headers from libboost-all-dev - it uses the headers of boost lockfree and optional which are part of libboost-dev
1 parent 9e4f6f2 commit be213a4

File tree

5 files changed

+10
-8
lines changed

5 files changed

+10
-8
lines changed

canopen_402_driver/package.xml

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,7 +9,10 @@
99

1010
<buildtool_depend>ament_cmake_ros</buildtool_depend>
1111

12-
<depend>boost</depend>
12+
<build_depend>libboost-all-dev</build_depend>
13+
14+
<build_export_depend>libboost-all-dev</build_export_depend>
15+
1316
<depend>canopen_base_driver</depend>
1417
<depend>canopen_core</depend>
1518
<depend>canopen_interfaces</depend>

canopen_base_driver/include/canopen_base_driver/lely_driver_bridge.hpp

Lines changed: 0 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -37,10 +37,6 @@
3737
#include <thread>
3838
#include <vector>
3939

40-
#include <boost/lockfree/queue.hpp>
41-
#include <boost/optional.hpp>
42-
#include <boost/thread.hpp>
43-
4440
#include "canopen_core/exchange.hpp"
4541

4642
using namespace std::chrono_literals;

canopen_base_driver/package.xml

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
<depend>rclcpp_lifecycle</depend>
1818
<depend>std_msgs</depend>
1919
<depend>std_srvs</depend>
20-
<depend>boost</depend>
2120
<depend>diagnostic_updater</depend>
2221

2322
<test_depend>ament_lint_auto</test_depend>

canopen_core/ConfigExtras.cmake

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -12,4 +12,4 @@
1212
# See the License for the specific language governing permissions and
1313
# limitations under the License.
1414
#
15-
find_package(Boost REQUIRED system thread)
15+
find_package(Boost REQUIRED thread)

canopen_core/package.xml

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -9,14 +9,18 @@
99

1010
<buildtool_depend>ament_cmake</buildtool_depend>
1111

12+
<build_depend>libboost-all-dev</build_depend>
13+
14+
<build_export_depend>libboost-all-dev</build_export_depend>
15+
1216
<depend>canopen_interfaces</depend>
1317
<depend>lely_core_libraries</depend>
18+
<depend>libboost-thread</depend>
1419
<depend>lifecycle_msgs</depend>
1520
<depend>rclcpp</depend>
1621
<depend>rclcpp_components</depend>
1722
<depend>rclcpp_lifecycle</depend>
1823
<depend>yaml_cpp_vendor</depend>
19-
<depend>boost</depend>
2024

2125
<test_depend>ament_lint_auto</test_depend>
2226

0 commit comments

Comments
 (0)