Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix the updown test. #1061

Merged
merged 1 commit into from
Aug 23, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
22 changes: 12 additions & 10 deletions nav2_system_tests/src/updown/test_updown_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,79 +50,81 @@ def generate_launch_description():

start_gazebo_cmd = launch.actions.ExecuteProcess(
cmd=['gzserver', '-s', 'libgazebo_ros_init.so',
world, ['__params:=', params_file]],
world,
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_robot_state_publisher_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('robot_state_publisher'),
'lib/robot_state_publisher/robot_state_publisher'),
urdf, ['__params:=', params_file]],
urdf,
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_map_server_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_map_server'),
'lib/nav2_map_server/map_server'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_localizer_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_amcl'),
'lib/nav2_amcl/amcl'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_world_model_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_world_model'),
'lib/nav2_world_model/world_model'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_dwb_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('dwb_controller'),
'lib/dwb_controller/dwb_controller'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_planner_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_navfn_planner'),
'lib/nav2_navfn_planner/navfn_planner'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_navigator_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_bt_navigator'),
'lib/nav2_bt_navigator/bt_navigator'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

start_controller_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_lifecycle_manager'),
'lib/nav2_lifecycle_manager/lifecycle_manager'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

startup_cmd = launch.actions.ExecuteProcess(
cmd=[
os.path.join(
get_package_prefix('nav2_system_tests'),
'lib/nav2_system_tests/test_updown'),
['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

startup_exit_event_handler = launch.actions.RegisterEventHandler(
Expand Down
56 changes: 56 additions & 0 deletions nav2_system_tests/src/updown/updownresults.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
#!/usr/bin/python3

# To use this script, run the `test_updown_reliablity` script and log the output
# > ./test_updown_reliablity |& tee /tmp/updown.log
# When the test is completed, pipe the log to this script to get a summary of the
# results
# > ./updownresults.py < /tmp/updown.log
#
# This reports the number of successful tests, but also the number of times the
# tests were able to make it to the active state as well as the shutdown state.
# It can frequently occur that the system makes all the lifecycle state transitions
# but has an error during the final process termination.

import sys

def main():
log = sys.stdin
test_count = 0
fail_count = 0
successful_bringup_count = 0
successful_shutdown_count = 0
for line in log.readlines():
if line.startswith('======= START OF RUN:'):
test_successful = True
shutdown_successful = False
bringup_successful = False

if line.startswith('======== END OF RUN:'):
test_count += 1
conclusion = ""
if bringup_successful:
successful_bringup_count += 1
conclusion = " but bringup was successful"
if shutdown_successful:
successful_shutdown_count +=1
conclusion = " but shutdown was successful"
if not test_successful:
fail_count += 1
print("Failure in test ", test_count, conclusion)

if '[ERROR]' in line:
test_successful = False

if 'The system is active' in line:
bringup_successful = True

if 'The system has been sucessfully shut down' in line:
shutdown_successful = True

print("Number of tests: ", test_count)
print("Number of successes: ", test_count-fail_count)
print("Number of successful bringups", successful_bringup_count)
print("Number of successful shutdowns", successful_shutdown_count)

if __name__ == '__main__':
main()