Skip to content

Commit

Permalink
Fixing linter errors, accidentally commited.
Browse files Browse the repository at this point in the history
  • Loading branch information
Carl Delsey committed Aug 23, 2019
1 parent 18bf2a6 commit c1b4fe4
Show file tree
Hide file tree
Showing 2 changed files with 33 additions and 17 deletions.
16 changes: 8 additions & 8 deletions nav2_system_tests/src/updown/test_updown_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -68,63 +68,63 @@ def generate_launch_description():
os.path.join(
get_package_prefix('nav2_map_server'),
'lib/nav2_map_server/map_server'),
'--ros-args', ['__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'),
'--ros-args', ['__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'),
'--ros-args', ['__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'),
'--ros-args', ['__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'),
'--ros-args', ['__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'),
'--ros-args', ['__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'),
'--ros-args', ['__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'),
'--ros-args', ['__params:=', params_file]],
'--ros-args', ['__params:=', params_file]],
cwd=[launch_dir], output='screen')

startup_exit_event_handler = launch.actions.RegisterEventHandler(
Expand Down
34 changes: 25 additions & 9 deletions nav2_system_tests/src/updown/updownresults.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,18 @@
#!/usr/bin/python3
# Copyright (c) 2019 Intel Corporation
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.


# To use this script, run the `test_updown_reliablity` script and log the output
# > ./test_updown_reliablity |& tee /tmp/updown.log
Expand All @@ -13,6 +27,7 @@

import sys


def main():
log = sys.stdin
test_count = 0
Expand All @@ -27,16 +42,16 @@ def main():

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

if '[ERROR]' in line:
test_successful = False
Expand All @@ -47,10 +62,11 @@ def main():
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)
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()

0 comments on commit c1b4fe4

Please sign in to comment.