Skip to content

Commit ffe496e

Browse files
Tony NajjarHovorunB
andauthored
Amrfm 1234 system test (ros-navigation#236)
* initial commit * many changes * increase costmap dim * fix executegoal goal * add camera server to test * format * [AMRFM-1318] Initial commit * fixes * remove other tests * Revert "Merge branch 'task_AMRFM-1318_make_nav2_navigator_current_goal_private' into AMRFM-1234-system-test" This reverts commit 980db3ef3630fdc7d271da76659fc17df848d145, reversing changes made to 1eec061f7bbafbbf473e0fd301c210b939f934ad. * remove readme * add amr_id * fix PR comments * refactoring * fix timeout Co-authored-by: HovorunB <[email protected]>
1 parent 0092abb commit ffe496e

File tree

7 files changed

+450
-5
lines changed

7 files changed

+450
-5
lines changed

amr_bringup/launch/camera_server_bringup.launch.py

Lines changed: 1 addition & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -195,11 +195,7 @@ def generate_launch_description():
195195
condition=IfCondition(LaunchConfiguration("use_path_manager")),
196196
),
197197
ExecuteProcess(
198-
cmd=[
199-
"python3",
200-
"-m",
201-
"lv.navigation.costmap.costmap_to_ros_bridge",
202-
],
198+
cmd=["python3", "-m", "lv.navigation.costmap.costmap_to_ros_bridge",],
203199
cwd=deep_cv_dir,
204200
output="screen",
205201
name="costmap_to_ros_bridge",

amr_system_tests/CMakeLists.txt

Lines changed: 53 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,53 @@
1+
cmake_minimum_required(VERSION 3.5)
2+
project(amr_system_tests)
3+
4+
find_package(ament_cmake REQUIRED)
5+
find_package(nav2_common REQUIRED)
6+
find_package(rclcpp REQUIRED)
7+
find_package(std_msgs REQUIRED)
8+
find_package(nav2_util REQUIRED)
9+
find_package(nav2_map_server REQUIRED)
10+
find_package(nav2_msgs REQUIRED)
11+
find_package(nav_msgs REQUIRED)
12+
find_package(visualization_msgs REQUIRED)
13+
find_package(geometry_msgs REQUIRED)
14+
find_package(std_msgs REQUIRED)
15+
find_package(tf2_geometry_msgs REQUIRED)
16+
find_package(gazebo_ros_pkgs REQUIRED)
17+
find_package(nav2_lifecycle_manager REQUIRED)
18+
find_package(rclpy REQUIRED)
19+
find_package(nav2_navfn_planner REQUIRED)
20+
find_package(nav2_planner REQUIRED)
21+
find_package(navigation2)
22+
find_package(angles REQUIRED)
23+
24+
nav2_package()
25+
26+
set(dependencies
27+
rclcpp
28+
nav2_util
29+
nav2_map_server
30+
nav2_msgs
31+
nav_msgs
32+
visualization_msgs
33+
nav2_lifecycle_manager
34+
gazebo_ros_pkgs
35+
geometry_msgs
36+
std_msgs
37+
tf2_geometry_msgs
38+
rclpy
39+
nav2_planner
40+
nav2_navfn_planner
41+
angles
42+
)
43+
44+
if(BUILD_TESTING)
45+
#find_package(ament_lint_auto REQUIRED)
46+
#ament_lint_auto_find_test_dependencies()
47+
#find_package(ament_cmake_gtest REQUIRED)
48+
#find_package(ament_cmake_pytest REQUIRED)
49+
add_subdirectory(src/system)
50+
51+
endif()
52+
53+
ament_package()

amr_system_tests/package.xml

Lines changed: 65 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,65 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>amr_system_tests</name>
5+
<version>0.4.7</version>
6+
<description>TODO</description>
7+
<maintainer email="[email protected]">Carlos Orduno</maintainer>
8+
<license>Apache-2.0</license>
9+
10+
<buildtool_depend>ament_cmake</buildtool_depend>
11+
<build_depend>nav2_common</build_depend>
12+
13+
<build_depend>rclcpp</build_depend>
14+
<build_depend>rclpy</build_depend>
15+
<build_depend>nav2_util</build_depend>
16+
<build_depend>nav2_map_server</build_depend>
17+
<build_depend>nav2_msgs</build_depend>
18+
<build_depend>nav2_lifecycle_manager</build_depend>
19+
<build_depend>nav2_navfn_planner</build_depend>
20+
<build_depend>nav_msgs</build_depend>
21+
<build_depend>visualization_msgs</build_depend>
22+
<build_depend>launch_ros</build_depend>
23+
<build_depend>launch_testing</build_depend>
24+
<build_depend>geometry_msgs</build_depend>
25+
<build_depend>std_msgs</build_depend>
26+
<build_depend>tf2_geometry_msgs</build_depend>
27+
<build_depend>gazebo_ros_pkgs</build_depend>
28+
<build_depend>launch_ros</build_depend>
29+
<build_depend>launch_testing</build_depend>
30+
<build_depend>nav2_planner</build_depend>
31+
32+
<exec_depend>launch_ros</exec_depend>
33+
<exec_depend>launch_testing</exec_depend>
34+
<exec_depend>rclcpp</exec_depend>
35+
<exec_depend>rclpy</exec_depend>
36+
<exec_depend>nav2_bringup</exec_depend>
37+
<exec_depend>nav2_util</exec_depend>
38+
<exec_depend>nav2_map_server</exec_depend>
39+
<exec_depend>nav2_msgs</exec_depend>
40+
<exec_depend>nav2_lifecycle_manager</exec_depend>
41+
<exec_depend>nav2_navfn_planner</exec_depend>
42+
<exec_depend>nav_msgs</exec_depend>
43+
<exec_depend>visualization_msgs</exec_depend>
44+
<exec_depend>geometry_msgs</exec_depend>
45+
<exec_depend>std_msgs</exec_depend>
46+
<exec_depend>tf2_geometry_msgs</exec_depend>
47+
<exec_depend>gazebo_ros_pkgs</exec_depend>
48+
<exec_depend>navigation2</exec_depend>
49+
<exec_depend>lcov</exec_depend>
50+
<exec_depend>robot_state_publisher</exec_depend>
51+
<exec_depend>nav2_planner</exec_depend>
52+
53+
<test_depend>ament_lint_common</test_depend>
54+
<test_depend>ament_lint_auto</test_depend>
55+
<test_depend>ament_cmake_gtest</test_depend>
56+
<test_depend>ament_cmake_pytest</test_depend>
57+
<test_depend>launch</test_depend>
58+
<test_depend>launch_ros</test_depend>
59+
<test_depend>launch_testing</test_depend>
60+
<test_depend>python3-zmq</test_depend>
61+
62+
<export>
63+
<build_type>ament_cmake</build_type>
64+
</export>
65+
</package>
Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,7 @@
1+
2+
ament_add_test(test_amr_gazebo_simulation
3+
GENERATE_RESULT_FOR_RETURN_CODE_ZERO
4+
COMMAND "${CMAKE_CURRENT_SOURCE_DIR}/test_system_launch.py"
5+
WORKING_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}"
6+
TIMEOUT 180
7+
)
Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,3 @@
1+
# AMR System Tests
2+
3+
This is a 'top level' system test which will use Gazebo to simulate a Robot moving from an known initial starting position to a goal pose.
Lines changed: 73 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,73 @@
1+
#!/usr/bin/env python3
2+
3+
# Copyright (c) 2018 Intel Corporation
4+
# Copyright (c) 2020 Florian Gramss
5+
#
6+
# Licensed under the Apache License, Version 2.0 (the "License");
7+
# you may not use this file except in compliance with the License.
8+
# You may obtain a copy of the License at
9+
#
10+
# http://www.apache.org/licenses/LICENSE-2.0
11+
#
12+
# Unless required by applicable law or agreed to in writing, software
13+
# distributed under the License is distributed on an "AS IS" BASIS,
14+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15+
# See the License for the specific language governing permissions and
16+
# limitations under the License.
17+
18+
import os
19+
import sys
20+
21+
from ament_index_python.packages import get_package_share_directory
22+
23+
from launch import LaunchDescription
24+
from launch import LaunchService
25+
from launch.actions import (
26+
ExecuteProcess,
27+
IncludeLaunchDescription,
28+
SetEnvironmentVariable,
29+
)
30+
from launch.launch_description_sources import PythonLaunchDescriptionSource
31+
from launch_testing.legacy import LaunchTestService
32+
33+
34+
def generate_launch_description():
35+
bringup_dir = get_package_share_directory("amr_bringup")
36+
37+
return LaunchDescription(
38+
[
39+
SetEnvironmentVariable("RCUTILS_LOGGING_USE_STDOUT", "1"),
40+
IncludeLaunchDescription(
41+
PythonLaunchDescriptionSource(
42+
os.path.join(bringup_dir, "launch/camera_server_bringup.launch.py")
43+
)
44+
),
45+
IncludeLaunchDescription(
46+
PythonLaunchDescriptionSource(
47+
os.path.join(bringup_dir, "launch/amr_simulation_gazebo.launch.py")
48+
),
49+
launch_arguments={"gui": "false", "amr_id": "2"}.items(),
50+
),
51+
]
52+
)
53+
54+
55+
def main(argv=sys.argv[1:]):
56+
ld = generate_launch_description()
57+
58+
test1_action = ExecuteProcess(
59+
cmd=["./tester_node.py", "--namespace=agv2"],
60+
cwd=os.path.dirname(os.path.realpath(__file__)),
61+
name="tester_node",
62+
output="screen",
63+
)
64+
65+
lts = LaunchTestService()
66+
lts.add_test_action(ld, test1_action)
67+
ls = LaunchService(argv=argv)
68+
ls.include_launch_description(ld)
69+
return lts.run(ls)
70+
71+
72+
if __name__ == "__main__":
73+
sys.exit(main())

0 commit comments

Comments
 (0)