1
- cmake_minimum_required (VERSION 3.5 )
1
+ cmake_minimum_required (VERSION 3.20 )
2
2
project (moveit_visual_tools)
3
3
4
4
find_package (moveit_common REQUIRED)
5
5
moveit_package()
6
6
7
7
# Load all dependencies required for this package
8
8
find_package (Boost REQUIRED system )
9
+ find_package (Bullet REQUIRED)
9
10
find_package (Eigen3 REQUIRED)
10
11
find_package (geometry_msgs REQUIRED)
11
12
find_package (graph_msgs REQUIRED)
@@ -19,21 +20,18 @@ find_package(tf2_eigen REQUIRED)
19
20
find_package (tf2_ros REQUIRED)
20
21
find_package (trajectory_msgs REQUIRED)
21
22
find_package (visualization_msgs REQUIRED)
22
-
23
- set (THIS_PACKAGE_INCLUDE_DEPENDS
24
- Boost
25
- geometry_msgs
26
- graph_msgs
27
- moveit_core
28
- moveit_ros_planning
29
- rclcpp
30
- rviz_visual_tools
31
- std_msgs
32
- tf2_eigen
33
- tf2_ros
34
- trajectory_msgs
35
- visualization_msgs
36
- )
23
+ find_package (QT NAMES Qt6 Qt5 COMPONENTS Widgets Core Core5Compat)
24
+ if (${QT_VERSION} EGUAL 6)
25
+ find_package (Qt{QT_VERSION_MAJOR}$ REQUIRED COMPONENTS Widgets Core Core5Compat)
26
+ elseif ()#qt5
27
+ find_package (Qt{QT_VERSION_MAJOR}$ REQUIRED COMPONENTS Widgets Core)
28
+ if (${QT_VERSION} VERSION_LESS 5.15.0)
29
+ function (qt_wrap_cpp out)
30
+ qt5_wrap_cpp(_sources ${ARGN} )
31
+ set ("${out} " ${_sources} PARENT_SCOPE)
32
+ endfunction ()
33
+ endif ()
34
+ endif ()
37
35
38
36
# Visualization Tools Library
39
37
add_library (${PROJECT_NAME} SHARED
@@ -44,23 +42,74 @@ add_library(${PROJECT_NAME} SHARED
44
42
45
43
target_include_directories (${PROJECT_NAME}
46
44
PUBLIC $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR} /include >
47
- PUBLIC $<INSTALL_INTERFACE:include >
45
+ PUBLIC $<INSTALL_INTERFACE:include > ${BULLET_INCLUDE_DIR}
48
46
)
49
- ament_target_dependencies(${PROJECT_NAME} ${THIS_PACKAGE_INCLUDE_DEPENDS} )
50
47
51
- # Demo executable
52
- add_executable (${PROJECT_NAME} _demo
53
- src/${PROJECT_NAME} _demo.cpp
54
- )
55
- target_link_libraries (${PROJECT_NAME} _demo
56
- ${PROJECT_NAME}
48
+ target_link_libraries (moveit_visual_tools PUBLIC
49
+ ${BULLET_LIBRARIES}
50
+ ${geometry_msgs_TARGETS}
51
+ ${graph_msgs_TARGETS}
52
+ ${std_msgs_TARGETS}
53
+ ${trajectory_msgs_TARGETS}
54
+ ${visualization_msgs_TARGETS}
55
+ Qt${QT_VERSION_MAJOR} ::Widgets
56
+ Qt${QT_VERSION_MAJOR} ::Core
57
+ Qt${QT_VERSION_MAJOR} ::Core5Compat
58
+ moveit_core::moveit_collision_detection
59
+ moveit_core::moveit_collision_detection_bullet
60
+ moveit_core::moveit_collision_detection_fcl
61
+ moveit_core::moveit_collision_distance_field
62
+ moveit_core::moveit_constraint_samplers
63
+ moveit_core::moveit_distance_field
64
+ moveit_core::moveit_dynamics_solver
65
+ moveit_core::moveit_exceptions
66
+ moveit_core::moveit_kinematic_constraints
67
+ moveit_core::moveit_kinematics_base
68
+ moveit_core::moveit_kinematics_metrics
69
+ moveit_core::moveit_macros
70
+ moveit_core::moveit_planning_interface
71
+ moveit_core::moveit_planning_scene
72
+ moveit_core::moveit_robot_model
73
+ moveit_core::moveit_robot_state
74
+ moveit_core::moveit_robot_trajectory
75
+ moveit_core::moveit_smoothing_base
76
+ moveit_core::moveit_test_utils
77
+ moveit_core::moveit_trajectory_processing
78
+ moveit_core::moveit_transforms
79
+ moveit_core::moveit_utils
80
+ moveit_ros_planning::default_request_adapter_parameters
81
+ moveit_ros_planning::default_response_adapter_parameters
82
+ moveit_ros_planning::kinematics_parameters
83
+ moveit_ros_planning::moveit_collision_plugin_loader
84
+ moveit_ros_planning::moveit_constraint_sampler_manager_loader
85
+ moveit_ros_planning::moveit_cpp
86
+ moveit_ros_planning::moveit_kinematics_plugin_loader
87
+ moveit_ros_planning::moveit_plan_execution
88
+ moveit_ros_planning::moveit_planning_pipeline
89
+ moveit_ros_planning::moveit_planning_pipeline_interfaces
90
+ moveit_ros_planning::moveit_planning_scene_monitor
91
+ moveit_ros_planning::moveit_rdf_loader
92
+ moveit_ros_planning::moveit_robot_model_loader
93
+ moveit_ros_planning::moveit_trajectory_execution_manager
94
+ moveit_ros_planning::planning_pipeline_parameters
95
+ moveit_ros_planning::srdf_publisher_node
96
+ rclcpp::rclcpp
97
+ rviz_visual_tools::rviz_visual_tools
98
+ rviz_visual_tools::rviz_visual_tools_gui
99
+ rviz_visual_tools::rviz_visual_tools_imarker_simple
100
+ rviz_visual_tools::rviz_visual_tools_remote_control
101
+ tf2_eigen::tf2_eigen
102
+ tf2_ros::static_transform_broadcaster_node
103
+ tf2_ros::tf2_ros
57
104
)
58
- ament_target_dependencies(${PROJECT_NAME} _demo ${THIS_PACKAGE_INCLUDE_DEPENDS} )
105
+
106
+
107
+
59
108
60
109
61
110
# Exports
62
111
ament_export_targets(export_${PROJECT_NAME} HAS_LIBRARY_TARGET)
63
- ament_export_dependencies( ${THIS_PACKAGE_INCLUDE_DEPENDS} )
112
+
64
113
65
114
#############
66
115
## Install ##
@@ -75,11 +124,7 @@ install(
75
124
LIBRARY DESTINATION lib
76
125
)
77
126
78
- # Install executables
79
- install (
80
- TARGETS ${PROJECT_NAME} _demo
81
- RUNTIME DESTINATION lib/${PROJECT_NAME}
82
- )
127
+
83
128
84
129
# Install header files
85
130
install (DIRECTORY include / DESTINATION include )
@@ -91,13 +136,36 @@ install(DIRECTORY launch resources DESTINATION share/${PROJECT_NAME})
91
136
## Testing ##
92
137
#############
93
138
94
- if (BUILD_TESTING)
139
+ if (0)#BUILD_TESTING)
140
+ # Demo executable
141
+ add_executable (${PROJECT_NAME} _demo
142
+ src/${PROJECT_NAME} _demo.cpp
143
+ )
144
+
145
+ target_include_directories (${PROJECT_NAME} _demo
146
+ PUBLIC ${BULLET_INCLUDE_DIR}
147
+ )
148
+ target_link_libraries (${PROJECT_NAME} _demo
149
+ ${BULLET_LIBRARIES} rclcpp::rclcpp
150
+ )
151
+ # Install executables
152
+ install (
153
+ TARGETS ${PROJECT_NAME} _demo
154
+ RUNTIME DESTINATION lib/${PROJECT_NAME}
155
+ )
95
156
find_package (ament_lint_auto REQUIRED)
96
157
set (ament_cmake_cppcheck_FOUND TRUE )
97
158
set (ament_cmake_cpplint_FOUND TRUE )
98
159
set (ament_cmake_uncrustify_FOUND TRUE )
99
160
set (ament_cmake_flake8_CONFIG_FILE ".ament_flake8.ini" )
100
161
ament_lint_auto_find_test_dependencies()
162
+
163
+ target_link_libraries (${PROJECT_NAME} _demo
164
+ ${BULLET_LIBRARIES}
165
+ rclcpp::rclcpp
166
+ ament_index_cpp::ament_index_cpp
167
+
168
+ )
101
169
endif ()
102
170
103
171
ament_package()
0 commit comments