From 714f45643ca2c403eff2c1462b1850ee5e1a5a84 Mon Sep 17 00:00:00 2001 From: Chris Lalancette Date: Fri, 22 Nov 2024 18:43:04 -0500 Subject: [PATCH] Add a python3-dev dependency to tf2_py. (#733) This is needed because it depends on Python.h being available, and it also calls find_package(Python3 Development). While we are in here, we also remove "Development" from the find_package(Python3) calls in tf2_geometry_msgs and tf2_sensor_msgs. In both of those cases, we only need the interpreter, not the header files. Signed-off-by: Chris Lalancette --- tf2_geometry_msgs/CMakeLists.txt | 2 +- tf2_py/package.xml | 1 + tf2_sensor_msgs/CMakeLists.txt | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/tf2_geometry_msgs/CMakeLists.txt b/tf2_geometry_msgs/CMakeLists.txt index d63e49d61..be704db72 100644 --- a/tf2_geometry_msgs/CMakeLists.txt +++ b/tf2_geometry_msgs/CMakeLists.txt @@ -25,7 +25,7 @@ endif() cmake_policy(SET CMP0094 NEW) set(Python3_FIND_UNVERSIONED_NAMES FIRST) -find_package(Python3 REQUIRED COMPONENTS Interpreter Development) +find_package(Python3 REQUIRED COMPONENTS Interpreter) find_package(geometry_msgs REQUIRED) find_package(orocos_kdl_vendor REQUIRED) diff --git a/tf2_py/package.xml b/tf2_py/package.xml index c898e8bc5..9c8f35626 100644 --- a/tf2_py/package.xml +++ b/tf2_py/package.xml @@ -16,6 +16,7 @@ ament_cmake geometry_msgs + python3-dev tf2 diff --git a/tf2_sensor_msgs/CMakeLists.txt b/tf2_sensor_msgs/CMakeLists.txt index 12542c1b6..72172e0d8 100644 --- a/tf2_sensor_msgs/CMakeLists.txt +++ b/tf2_sensor_msgs/CMakeLists.txt @@ -25,7 +25,7 @@ endif() cmake_policy(SET CMP0094 NEW) set(Python3_FIND_UNVERSIONED_NAMES FIRST) -find_package(Python3 REQUIRED COMPONENTS Interpreter Development) +find_package(Python3 REQUIRED COMPONENTS Interpreter) find_package(eigen3_cmake_module REQUIRED) find_package(Eigen3 REQUIRED)