diff --git a/rosbot_gazebo/test/test_diff_drive_simulation.py b/rosbot_gazebo/test/test_diff_drive_simulation.py index 7a2ef114..2bb1be44 100644 --- a/rosbot_gazebo/test/test_diff_drive_simulation.py +++ b/rosbot_gazebo/test/test_diff_drive_simulation.py @@ -67,7 +67,7 @@ def test_diff_drive_simulation(): time.sleep(3) # Wait 3 seconds for the velocity ​​to stabilize assert ( node.controller_odom_flag - ), "ROSbot does not move properly in x direction. Check rosbot_xl_base_controller!" + ), "ROSbot does not move properly in x direction. Check rosbot_base_controller!" assert ( node.ekf_odom_flag ), "ROSbot does not move properly in x direction. Check ekf_filter_node!" @@ -76,7 +76,7 @@ def test_diff_drive_simulation(): time.sleep(3) # Wait 3 seconds for the velocity ​​to stabilize assert ( node.controller_odom_flag - ), "ROSbot does not rotate properly. Check rosbot_xl_base_controller!" + ), "ROSbot does not rotate properly. Check rosbot_base_controller!" assert node.ekf_odom_flag, "ROSbot does not rotate properly. Check ekf_filter_node!" flag = node.scan_event.wait(timeout=20.0) diff --git a/rosbot_gazebo/test/test_mecanum_simulation.py b/rosbot_gazebo/test/test_mecanum_simulation.py index 4230cfcf..14a526a6 100644 --- a/rosbot_gazebo/test/test_mecanum_simulation.py +++ b/rosbot_gazebo/test/test_mecanum_simulation.py @@ -67,7 +67,7 @@ def test_mecanum_simulation(): time.sleep(3) # Wait 3 seconds for the velocity ​​to stabilize assert ( node.controller_odom_flag - ), "ROSbot does not move properly in x direction. Check rosbot_xl_base_controller!" + ), "ROSbot does not move properly in x direction. Check rosbot_base_controller!" assert ( node.ekf_odom_flag ), "ROSbot does not move properly in x direction. Check ekf_filter_node!" @@ -76,7 +76,7 @@ def test_mecanum_simulation(): time.sleep(3) # Wait 3 seconds for the velocity ​​to stabilize assert ( node.controller_odom_flag - ), "ROSbot does not move properly in y direction. Check rosbot_xl_base_controller!" + ), "ROSbot does not move properly in y direction. Check rosbot_base_controller!" assert ( node.ekf_odom_flag ), "ROSbot does not move properly in y direction. Check ekf_filter_node!" diff --git a/rosbot_gazebo/test/test_utils.py b/rosbot_gazebo/test/test_utils.py index 16b6b740..50f4918a 100644 --- a/rosbot_gazebo/test/test_utils.py +++ b/rosbot_gazebo/test/test_utils.py @@ -99,7 +99,7 @@ def ekf_callback(self, data: Odometry): if self.is_twist_ok(data.twist.twist): self.ekf_odom_flag = True else: - self.controller_odom_flag = False + self.ekf_odom_flag = False def lookup_transform_odom(self): try: