diff --git a/CMakeLists.txt b/CMakeLists.txt index e1004d2..96f9ff7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -132,24 +132,11 @@ if(BUILD_TESTING) target_link_libraries(${PROJECT_NAME}-test_message_traits ${PROJECT_NAME} rclcpp::rclcpp ${std_msgs_TARGETS}) endif() - # Provides PYTHON_EXECUTABLE_DEBUG - find_package(python_cmake_module REQUIRED) - find_package(PythonExtra REQUIRED) - set(_PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE}") - if(WIN32) - if(CMAKE_BUILD_TYPE STREQUAL "Debug") - set(_PYTHON_EXECUTABLE "${PYTHON_EXECUTABLE_DEBUG}") - endif() - endif() - # python tests with python interfaces of message filters find_package(ament_cmake_pytest REQUIRED) - ament_add_pytest_test(directed.py "test/directed.py" - PYTHON_EXECUTABLE "${_PYTHON_EXECUTABLE}") - ament_add_pytest_test(test_approxsync.py "test/test_approxsync.py" - PYTHON_EXECUTABLE "${_PYTHON_EXECUTABLE}") - ament_add_pytest_test(test_message_filters_cache.py "test/test_message_filters_cache.py" - PYTHON_EXECUTABLE "${_PYTHON_EXECUTABLE}") + ament_add_pytest_test(directed.py "test/directed.py") + ament_add_pytest_test(test_approxsync.py "test/test_approxsync.py") + ament_add_pytest_test(test_message_filters_cache.py "test/test_message_filters_cache.py") endif() ament_package() diff --git a/package.xml b/package.xml index 05c58cb..b087cfc 100644 --- a/package.xml +++ b/package.xml @@ -20,7 +20,6 @@ ament_cmake_python ament_cmake_ros - python_cmake_module rclcpp rcutils