Skip to content

Commit

Permalink
Remove duplicate tf for costmap tests (#4930)
Browse files Browse the repository at this point in the history
Signed-off-by: mini-1235 <[email protected]>
  • Loading branch information
mini-1235 authored Mar 4, 2025
1 parent 7e3ae16 commit 9677e68
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 3 deletions.
4 changes: 3 additions & 1 deletion nav2_costmap_2d/test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,7 @@ ament_add_test(plugin_container_tests
TEST_MAP=${TEST_MAP_DIR}/TenByTen.yaml
TEST_LAUNCH_DIR=${TEST_LAUNCH_DIR}
TEST_EXECUTABLE=$<TARGET_FILE:plugin_container_tests_exec>
STATIC_ODOM_TO_BASE_LINK=true
)

ament_add_test(test_costmap_publisher_exec
Expand All @@ -140,6 +141,7 @@ ament_add_test(test_costmap_publisher_exec
TEST_MAP=${TEST_MAP_DIR}/TenByTen.yaml
TEST_LAUNCH_DIR=${TEST_LAUNCH_DIR}
TEST_EXECUTABLE=$<TARGET_FILE:test_costmap_publisher_exec>
STATIC_ODOM_TO_BASE_LINK=true
)

ament_add_test(test_costmap_subscriber_exec
Expand All @@ -163,4 +165,4 @@ ament_add_test(test_costmap_subscriber_exec
# nav2_util::nav2_utils_core
# rclcpp::rclcpp
# tf2_ros::tf2_ros
# )
# )
7 changes: 5 additions & 2 deletions nav2_costmap_2d/test/integration/costmap_tests_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -76,13 +76,16 @@ def main(argv=sys.argv[1:]):
[
IncludeLaunchDescription(PythonLaunchDescriptionSource([launchFile])),
map_to_odom,
odom_to_base_link,
lifecycle_manager,
]
)
if os.getenv('STATIC_ODOM_TO_BASE_LINK') == 'true':
ld.add_action(odom_to_base_link)

test1_action = ExecuteProcess(
cmd=[testExecutable], name='costmap_tests', output='screen'
cmd=[testExecutable],
name='costmap_tests',
output='screen'
)

lts = LaunchTestService()
Expand Down

0 comments on commit 9677e68

Please sign in to comment.