Skip to content

Commit

Permalink
Make gazebo_ros_pkgs optional in nav2_system_tests
Browse files Browse the repository at this point in the history
* This allows users to build all of nav2 with new gazebo installed without any special flags
* Leverage common environment variable GZ_VERSION
* Add author warning when some tests are disabled
* Making gazebo classic optional is one of the first things to help migration

Signed-off-by: Ryan Friedman <[email protected]>
  • Loading branch information
Ryanf55 committed Feb 3, 2024
1 parent 18e9b2b commit 3c5784c
Show file tree
Hide file tree
Showing 4 changed files with 29 additions and 17 deletions.
36 changes: 23 additions & 13 deletions nav2_system_tests/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@ find_package(visualization_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(std_msgs REQUIRED)
find_package(tf2_geometry_msgs REQUIRED)
find_package(gazebo_ros_pkgs REQUIRED)
find_package(gazebo_ros_pkgs)
find_package(nav2_amcl REQUIRED)
find_package(nav2_lifecycle_manager REQUIRED)
find_package(rclpy REQUIRED)
Expand All @@ -37,7 +37,6 @@ set(dependencies
nav2_amcl
nav2_lifecycle_manager
nav2_behavior_tree
gazebo_ros_pkgs
geometry_msgs
std_msgs
tf2_geometry_msgs
Expand Down Expand Up @@ -100,6 +99,13 @@ install(FILES src/error_codes/smoother_plugins.xml
DESTINATION share/${PROJECT_NAME}
)

if(gazebo_ros_pkgs_FOUND)
list(APPEND dependencies gazebo_ros_pkgs)
else()
message(AUTHOR_WARNING "Some system tests are disabled because Gazebo Classic was not found. "
"GZ_VERSION is set to '$ENV{GZ_VERSION}'.")
endif()

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
Expand All @@ -109,19 +115,23 @@ if(BUILD_TESTING)

add_subdirectory(src/behavior_tree)
add_subdirectory(src/planning)
add_subdirectory(src/localization)
add_subdirectory(src/system)
add_subdirectory(src/system_failure)
add_subdirectory(src/updown)
add_subdirectory(src/waypoint_follower)
add_subdirectory(src/gps_navigation)
add_subdirectory(src/behaviors/spin)
add_subdirectory(src/behaviors/wait)
add_subdirectory(src/behaviors/backup)
add_subdirectory(src/behaviors/drive_on_heading)
add_subdirectory(src/behaviors/assisted_teleop)
add_subdirectory(src/costmap_filters)
add_subdirectory(src/error_codes)

if(gazebo_ros_pkgs_FOUND)
add_subdirectory(src/behaviors/assisted_teleop)
add_subdirectory(src/behaviors/backup)
add_subdirectory(src/behaviors/drive_on_heading)
add_subdirectory(src/behaviors/spin)
add_subdirectory(src/behaviors/wait)
add_subdirectory(src/costmap_filters)
add_subdirectory(src/gps_navigation)
add_subdirectory(src/localization)
add_subdirectory(src/system)
add_subdirectory(src/system_failure)
add_subdirectory(src/waypoint_follower)
endif()

install(DIRECTORY maps DESTINATION share/${PROJECT_NAME})

endif()
Expand Down
3 changes: 3 additions & 0 deletions nav2_system_tests/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,6 @@ Most tests in this package will spin up Gazebo instances of a robot in an enviro
- Testing system failures are properly recorded and can be recovered from

This is primarily for use in Nav2 CI to establish a high degree of maintainer confidence when merging in large architectural changes to the Nav2 project. However, this is also useful to test installs of Nav2 locally or for additional information.

To disable system tests depending on Gazebo Classic, which is end of life January 29th, 2025,
set the environment variable `GZ_VERSION` to your chosen GZ name, such as `ignition` or `harmonic`.
4 changes: 2 additions & 2 deletions nav2_system_tests/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
<build_depend>geometry_msgs</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>tf2_geometry_msgs</build_depend>
<build_depend>gazebo_ros_pkgs</build_depend>
<build_depend condition="$GZ_VERSION == ''">gazebo_ros_pkgs</build_depend>
<build_depend>launch_ros</build_depend>
<build_depend>launch_testing</build_depend>
<build_depend>nav2_planner</build_depend>
Expand All @@ -48,7 +48,7 @@
<exec_depend>nav2_amcl</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>tf2_geometry_msgs</exec_depend>
<exec_depend>gazebo_ros_pkgs</exec_depend>
<exec_depend condition="$GZ_VERSION == ''">gazebo_ros_pkgs</exec_depend>
<exec_depend>navigation2</exec_depend>
<exec_depend>lcov</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
Expand Down
3 changes: 1 addition & 2 deletions nav2_system_tests/src/updown/test_updown_reliability
Original file line number Diff line number Diff line change
Expand Up @@ -13,9 +13,8 @@ do
# Bound the time of the bringup/shutdown in case it hangs
timeout 100 ./start_nav2

# Make sure there aren't any stray gazebo or ros2 processes hanging around
# Make sure there aren't any stray ros2 processes hanging around
# that were not properly killed by the launch script
#kill -9 $(pgrep gzserver) &> /dev/null
kill -9 $(pgrep ros2) &> /dev/null

echo "======== END OF RUN: $i =========="
Expand Down

0 comments on commit 3c5784c

Please sign in to comment.