@@ -13,15 +13,16 @@ endif()
13
13
find_package (ament_cmake REQUIRED )
14
14
find_package (ament_index_cpp REQUIRED )
15
15
find_package (geometry_msgs REQUIRED )
16
- find_package (Qt5 REQUIRED COMPONENTS Widgets )
16
+ find_package (QT NAMES Qt5 Qt6 REQUIRED COMPONENTS Widgets Core )
17
+ find_package (Qt${QT_VERSION_MAJOR} REQUIRED COMPONENTS Widgets Core )
17
18
find_package (rcl_interfaces REQUIRED )
18
19
find_package (rclcpp REQUIRED )
19
20
find_package (rclcpp_action REQUIRED )
20
21
find_package (rosidl_default_generators REQUIRED )
21
22
find_package (std_msgs REQUIRED )
22
23
find_package (std_srvs REQUIRED )
23
24
24
- include_directories (include ${Qt5Widgets_INCLUDE_DIRS } )
25
+ include_directories (include ${Qt${QT_VERSION_MAJOR}Widgets_INCLUDE_DIRS } )
25
26
26
27
rosidl_generate_interfaces (${PROJECT_NAME}
27
28
"action/RotateAbsolute.action"
@@ -33,7 +34,7 @@ rosidl_generate_interfaces(${PROJECT_NAME}
33
34
"srv/TeleportAbsolute.srv"
34
35
"srv/TeleportRelative.srv" )
35
36
36
- qt5_wrap_cpp ( turtlesim_node_MOCS include /turtlesim/turtle_frame.hpp )
37
+ set ( CMAKE_AUTOMOC ON )
37
38
38
39
rosidl_get_typesupport_target (cpp_typesupport_target "${PROJECT_NAME} " "rosidl_typesupport_cpp" )
39
40
@@ -47,8 +48,9 @@ target_link_libraries(turtlesim_node PRIVATE
47
48
ament_index_cpp::ament_index_cpp
48
49
${cpp_typesupport_target}
49
50
${geometry_msgs_TARGETS}
50
- Qt5::Widgets
51
51
${rcl_interfaces_TARGETS}
52
+ Qt${QT_VERSION_MAJOR}::Core
53
+ Qt${QT_VERSION_MAJOR}::Widgets
52
54
rclcpp::rclcpp
53
55
rclcpp_action::rclcpp_action
54
56
${std_srvs_TARGETS}
0 commit comments