File tree Expand file tree Collapse file tree 1 file changed +11
-14
lines changed Expand file tree Collapse file tree 1 file changed +11
-14
lines changed Original file line number Diff line number Diff line change 1
- diff --git a/CMakeLists.txt b/CMakeLists.txt
2
- index 99aab735d..ca550918a 100644
3
- --- a/CMakeLists.txt
4
- +++ b/CMakeLists.txt
5
- @@ -1,6 +1,10 @@
6
- cmake_minimum_required(VERSION 3.5)
7
- project(moveit_py)
1
+ diff --git a/src/moveit/moveit_py_utils/CMakeLists.txt b/src/moveit/moveit_py_utils/CMakeLists.txt
2
+ index 132da7425..5e6564626 100644
3
+ --- a/src/moveit/moveit_py_utils/CMakeLists.txt
4
+ +++ b/src/moveit/moveit_py_utils/CMakeLists.txt
5
+ @@ -8,6 +8,7 @@ set_target_properties(moveit_py_utils PROPERTIES VERSION
8
6
9
- + if(APPLE)
10
- + set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -Wl,-undefined,dynamic_lookup")
11
- + endif()
12
- +
13
- find_package(ament_cmake REQUIRED)
14
- find_package(rclcpp REQUIRED)
15
- find_package(rclpy REQUIRED)
7
+ ament_target_dependencies(moveit_py_utils rclcpp moveit_msgs geometry_msgs
8
+ pybind11)
9
+ + target_link_libraries(moveit_py_utils Python3::Module)
10
+
11
+ install(
12
+ TARGETS moveit_py_utils
You can’t perform that action at this time.
0 commit comments