mirror of
https://github.com/moveit/moveit_task_constructor.git
synced 2025-09-27 00:29:13 +08:00
drop internal pybind11
drop internal pybind11 use use ros pybynd11_vendor
This commit is contained in:
parent
7e1303dee1
commit
cf0e89e25d
7
.gitmodules
vendored
7
.gitmodules
vendored
@ -1,8 +1,3 @@
|
||||
[submodule "core/python/pybind11"]
|
||||
path = core/python/pybind11
|
||||
url = https://github.com/pybind/pybind11
|
||||
branch = smart_holder
|
||||
shallow = true
|
||||
[submodule "core/src/scope_guard"]
|
||||
path = core/src/scope_guard
|
||||
url = https://github.com/ricab/scope_guard
|
||||
url = https://github.com/ricab/scope_guard
|
@ -12,6 +12,8 @@ find_package(moveit_core REQUIRED)
|
||||
find_package(moveit_ros_planning REQUIRED)
|
||||
find_package(moveit_ros_planning_interface REQUIRED)
|
||||
find_package(moveit_task_constructor_msgs REQUIRED)
|
||||
find_package(pybind11_vendor REQUIRED)
|
||||
find_package(pybind11 REQUIRED)
|
||||
find_package(py_binding_tools REQUIRED)
|
||||
find_package(rclcpp REQUIRED)
|
||||
find_package(rviz_marker_tools REQUIRED)
|
||||
|
@ -1,9 +0,0 @@
|
||||
# pybind11 must use the ROS python version
|
||||
set(PYBIND11_PYTHON_VERSION ${PYTHON_VERSION})
|
||||
|
||||
if(@INSTALLSPACE@)
|
||||
include(${CMAKE_CURRENT_LIST_DIR}/pybind11Config.cmake)
|
||||
else()
|
||||
# in build space, directly include pybind11 directory
|
||||
add_subdirectory(${CMAKE_CURRENT_LIST_DIR}/../pybind11 ${CMAKE_CURRENT_BINARY_DIR}/pybind11)
|
||||
endif()
|
@ -13,6 +13,8 @@
|
||||
|
||||
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||
<buildtool_depend>ament_cmake_python</buildtool_depend>
|
||||
<build_depend>pybind11_vendor</build_depend>
|
||||
|
||||
|
||||
<depend>fmt</depend>
|
||||
<depend>geometry_msgs</depend>
|
||||
|
@ -3,25 +3,9 @@
|
||||
find_package(ament_cmake_python REQUIRED)
|
||||
find_package(Python3 COMPONENTS Interpreter Development)
|
||||
# pybind11 must use the ROS python version
|
||||
set(PYBIND11_PYTHON_VERSION ${PYTHON_VERSION})
|
||||
|
||||
# Use minimum-size optimization for pybind11 bindings
|
||||
add_compile_options("-Os")
|
||||
|
||||
# configure pybind11 install for use by downstream packages in install space
|
||||
set(PYBIND11_INSTALL ON CACHE INTERNAL "Install pybind11")
|
||||
set(CMAKE_INSTALL_INCLUDEDIR include/moveit/python)
|
||||
set(PYBIND11_CMAKECONFIG_INSTALL_DIR share/${PROJECT_NAME}/cmake
|
||||
CACHE INTERNAL "install path for pybind11 cmake files")
|
||||
|
||||
# source pybind11 folder, which exposes its targets and installs them
|
||||
if(NOT EXISTS "${CMAKE_CURRENT_SOURCE_DIR}/pybind11/CMakeLists.txt")
|
||||
message("Missing content of submodule pybind11: Use 'git clone --recurse-submodule' in future.\n"
|
||||
"Checking out content automatically")
|
||||
execute_process(COMMAND git submodule init WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
execute_process(COMMAND git submodule update WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
endif()
|
||||
add_subdirectory(pybind11)
|
||||
find_package(pybind11_vendor REQUIRED)
|
||||
find_package(pybind11 REQUIRED)
|
||||
|
||||
# C++ wrapper code
|
||||
add_subdirectory(bindings)
|
||||
|
@ -1 +0,0 @@
|
||||
Subproject commit f4bc71f981d4eb2dd780215fd3c5a7420f1f03aa
|
Loading…
Reference in New Issue
Block a user