Skip to content

Commit

Permalink
divide assertion
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Nov 3, 2023
1 parent 699f736 commit 37eb7ae
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 5 deletions.
8 changes: 6 additions & 2 deletions rosbot_gazebo/test/test_diff_drive_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,12 +67,16 @@ def test_diff_drive_simulation():
node.set_destination_speed(0.9, 0.0, 0.0)
controller_flag = node.controller_odom_event.wait(timeout=20.0)
ekf_flag = node.ekf_odom_event.wait(timeout=20.0)
assert controller_flag and ekf_flag, "ROSbot does not move properly in x direction!"
assert (
controller_flag
), "ROSbot does not move properly in x direction. Check rosbot_base_controller!"
assert ekf_flag, "ROSbot does not move properly in x direction. Check ekf_filter_node!"

node.set_destination_speed(0.0, 0.0, 3.0)
controller_flag = node.controller_odom_event.wait(timeout=20.0)
ekf_flag = node.ekf_odom_event.wait(timeout=20.0)
assert controller_flag and ekf_flag, "ROSbot does not rotate properly!"
assert controller_flag, "ROSbot does not rotate properly. Check rosbot_base_controller!"
assert ekf_flag, "ROSbot does not rotate properly. Check ekf_filter_node!"

flag = node.scan_event.wait(timeout=20.0)
assert flag, "ROSbot's lidar does not work properly!"
Expand Down
13 changes: 10 additions & 3 deletions rosbot_gazebo/test/test_mecanum_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -68,17 +68,24 @@ def test_mecanum_simulation():
node.set_destination_speed(0.9, 0.0, 0.0)
controller_flag = node.controller_odom_event.wait(timeout=20.0)
ekf_flag = node.ekf_odom_event.wait(timeout=20.0)
assert controller_flag and ekf_flag, "ROSbot does not move properly in x direction!"
assert (
controller_flag
), "ROSbot does not move properly in x direction. Check rosbot_base_controller!"
assert ekf_flag, "ROSbot does not move properly in x direction. Check ekf_filter_node!"

node.set_destination_speed(0.0, 0.9, 0.0)
controller_flag = node.controller_odom_event.wait(timeout=20.0)
ekf_flag = node.ekf_odom_event.wait(timeout=20.0)
assert controller_flag and ekf_flag, "ROSbot does not move properly in y direction!"
assert (
controller_flag
), "ROSbot does not move properly in y direction. Check rosbot_base_controller!"
assert ekf_flag, "ROSbot does not move properly in y direction. Check ekf_filter_node!"

node.set_destination_speed(0.0, 0.0, 3.0)
controller_flag = node.controller_odom_event.wait(timeout=20.0)
ekf_flag = node.ekf_odom_event.wait(timeout=20.0)
assert controller_flag and ekf_flag, "ROSbot does not rotate properly!"
assert controller_flag, "ROSbot does not rotate properly. Check rosbot_base_controller!"
assert ekf_flag, "ROSbot does not rotate properly. Check ekf_filter_node!"

flag = node.scan_event.wait(timeout=20.0)
assert flag, "ROSbot's lidar does not work properly!"
Expand Down

0 comments on commit 37eb7ae

Please sign in to comment.