-
Notifications
You must be signed in to change notification settings - Fork 1.3k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Switch nav2_collision_monitor to modern CMake idioms.
Signed-off-by: Chris Lalancette <[email protected]>
- Loading branch information
1 parent
a19dd01
commit 34cc452
Showing
4 changed files
with
119 additions
and
90 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,52 +1,60 @@ | ||
# Kinematics test | ||
ament_add_gtest(kinematics_test kinematics_test.cpp) | ||
ament_target_dependencies(kinematics_test | ||
${dependencies} | ||
) | ||
target_link_libraries(kinematics_test | ||
${monitor_library_name} | ||
rclcpp::rclcpp | ||
) | ||
|
||
# Data sources test | ||
ament_add_gtest(sources_test sources_test.cpp) | ||
ament_target_dependencies(sources_test | ||
${dependencies} | ||
) | ||
target_link_libraries(sources_test | ||
${monitor_library_name} | ||
rclcpp::rclcpp | ||
nav2_util::nav2_util_core | ||
${sensor_msgs_TARGETS} | ||
tf2_ros::tf2_ros | ||
) | ||
|
||
# Polygon shapes test | ||
ament_add_gtest(polygons_test polygons_test.cpp) | ||
ament_target_dependencies(polygons_test | ||
${dependencies} | ||
) | ||
target_link_libraries(polygons_test | ||
${monitor_library_name} | ||
${geometry_msgs_TARGETS} | ||
nav2_util::nav2_util_core | ||
rclcpp::rclcpp | ||
tf2_ros::tf2_ros | ||
) | ||
|
||
# Velocity Polygon test | ||
ament_add_gtest(velocity_polygons_test velocity_polygons_test.cpp) | ||
ament_target_dependencies(velocity_polygons_test | ||
${dependencies} | ||
) | ||
target_link_libraries(velocity_polygons_test | ||
${monitor_library_name} | ||
${geometry_msgs_TARGETS} | ||
nav2_util::nav2_util_core | ||
rclcpp::rclcpp | ||
tf2_ros::tf2_ros | ||
) | ||
|
||
# Collision Monitor node test | ||
ament_add_gtest(collision_monitor_node_test collision_monitor_node_test.cpp) | ||
ament_target_dependencies(collision_monitor_node_test | ||
${dependencies} | ||
) | ||
target_link_libraries(collision_monitor_node_test | ||
${monitor_library_name} | ||
${geometry_msgs_TARGETS} | ||
${nav2_msgs_TARGETS} | ||
nav2_util::nav2_util_core | ||
rclcpp::rclcpp | ||
${sensor_msgs_TARGETS} | ||
tf2_ros::tf2_ros | ||
${visualization_msgs_TARGETS} | ||
) | ||
# Collision Detector node test | ||
ament_add_gtest(collision_detector_node_test collision_detector_node_test.cpp) | ||
ament_target_dependencies(collision_detector_node_test | ||
${dependencies} | ||
) | ||
target_link_libraries(collision_detector_node_test | ||
${detector_library_name} | ||
) | ||
${geometry_msgs_TARGETS} | ||
nav2_util::nav2_util_core | ||
rclcpp::rclcpp | ||
${sensor_msgs_TARGETS} | ||
tf2_ros::tf2_ros | ||
${visualization_msgs_TARGETS} | ||
) |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters