diff --git a/bindings/python/RobotInterface/CMakeLists.txt b/bindings/python/RobotInterface/CMakeLists.txt index 078c158166..7b9011f73a 100644 --- a/bindings/python/RobotInterface/CMakeLists.txt +++ b/bindings/python/RobotInterface/CMakeLists.txt @@ -20,13 +20,21 @@ if(TARGET BipedalLocomotion::RobotInterface AND TARGET BipedalLocomotion::RobotInterfaceYarpImplementation AND TARGET BipedalLocomotion::PerceptionInterfaceYarpImplementation) - FetchContent_Declare( - cvnp - GIT_REPOSITORY https://github.com/pthom/cvnp - GIT_TAG e91b2f04e7b7e8c2858ef4d45b434591aa6c0e25 - ) - - FetchContent_MakeAvailable(cvnp) + set(cvnp_target_link ) + + # This compiles only if pybind11 is at least v2.7.0 + # Indeed we need a feature in pybind that has been introduced by this commit + # https://github.com/pybind/pybind11/commit/74a767d42921001fc4569ecee3b8726383c42ad4 + # https://github.com/pybind/pybind11/pull/2864 + if (${pybind11_VERSION} VERSION_GREATER_EQUAL "2.7.0") + FetchContent_Declare( + cvnp + GIT_REPOSITORY https://github.com/pthom/cvnp + GIT_TAG e91b2f04e7b7e8c2858ef4d45b434591aa6c0e25 + ) + FetchContent_MakeAvailable(cvnp) + set(cvnp_target_link cvnp) + endif() set(H_PREFIX include/BipedalLocomotion/bindings/RobotInterface) @@ -34,7 +42,10 @@ if(TARGET BipedalLocomotion::RobotInterface NAME PerceptionInterfaceBindings SOURCES src/PerceptionModule.cpp src/CameraBridge.cpp HEADERS ${H_PREFIX}/PerceptionModule.h ${H_PREFIX}/CameraBridge.h - LINK_LIBRARIES BipedalLocomotion::PerceptionInterface BipedalLocomotion::PerceptionInterfaceYarpImplementation cvnp + LINK_LIBRARIES BipedalLocomotion::PerceptionInterface BipedalLocomotion::PerceptionInterfaceYarpImplementation ${cvnp_target_link} + ADDITIONAL_COMPILE_DEFINITIONS pybind11_VERSION_MAJOR=${pybind11_VERSION_MAJOR} + pybind11_VERSION_MINOR=${pybind11_VERSION_MINOR} + pybind11_VERSION_PATCH=${pybind11_VERSION_PATCH} ) endif() diff --git a/bindings/python/RobotInterface/src/CameraBridge.cpp b/bindings/python/RobotInterface/src/CameraBridge.cpp index 56b272662e..5be5076b21 100644 --- a/bindings/python/RobotInterface/src/CameraBridge.cpp +++ b/bindings/python/RobotInterface/src/CameraBridge.cpp @@ -5,8 +5,21 @@ * distributed under the terms of the BSD-3-Clause license. */ +#define PYBIND_VERSION_AT_LEAST(x, y, z) \ + ((pybind11_VERSION_MAJOR > x) \ + || ((pybind11_VERSION_MAJOR >= x) && (pybind11_VERSION_MINOR > y)) \ + || ((pybind11_VERSION_MAJOR >= x) && (pybind11_VERSION_MINOR >= y) \ + && (pybind11_VERSION_PATCH > z))) + // NumPy/OpenCV compatibility + +// This compiles only if pybind11 is at least v2.7.0 +// Indeed we need a feature in pybind that has been introduced by this commit +// https://github.com/pybind/pybind11/commit/74a767d42921001fc4569ecee3b8726383c42ad4 +// https://github.com/pybind/pybind11/pull/2864 +#if PYBIND_VERSION_AT_LEAST(2, 7, 0) #include +#endif // PYBIND_VERSION_AT_LEAST(2, 7, 0) #include #include @@ -50,13 +63,19 @@ void CreateICameraBridge(pybind11::module& module) .def_readwrite("sensors_list", &CameraBridgeMetaData::sensorsList) .def_readwrite("bridge_options", &CameraBridgeMetaData::bridgeOptions); - py::class_(module, "ICameraBridge") + py::class_ iCameraBridge(module, "ICameraBridge"); + iCameraBridge .def( "initialize", [](ICameraBridge& impl, std::shared_ptr handler) -> bool { return impl.initialize(handler); }, py::arg("handler")) + .def("get_meta_data", &ICameraBridge::getMetaData) + .def("is_valid", &ICameraBridge::isValid); + +#if PYBIND_VERSION_AT_LEAST(2, 7, 0) + iCameraBridge .def( "get_color_image", [](ICameraBridge& impl, const std::string& camName) { @@ -72,9 +91,8 @@ void CreateICameraBridge(pybind11::module& module) ret.first = impl.getDepthImage(camName, ret.second); return ret; }, - py::arg("cam_name")) - .def("get_meta_data", &ICameraBridge::getMetaData) - .def("is_valid", &ICameraBridge::isValid); + py::arg("cam_name")); +#endif // PYBIND_VERSION_AT_LEAST(2, 7, 0) } void CreateYarpCameraBridge(pybind11::module& module)