Skip to content

Commit

Permalink
update
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Dec 1, 2023
1 parent 0fca432 commit 3d1887b
Show file tree
Hide file tree
Showing 3 changed files with 22 additions and 7 deletions.
10 changes: 8 additions & 2 deletions rosbot_gazebo/test/test_diff_drive_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,10 @@ def test_diff_drive_simulation():
# 0.9 m/s and 3.0 rad/s are controller's limits defined in
# rosbot_controller/config/diff_drive_controller.yaml
node.set_destination_speed(0.9, 0.0, 0.0)
assert node.vel_stabilization_time_event.wait(timeout=20.0), "Simulation crashed!"
assert node.vel_stabilization_time_event.wait(timeout=20.0), (
"The simulation is running slowly or has crashed! The time elapsed since setting the"
f" target speed is: {(node.current_time - node.goal_received_time):.1f}."
)
assert (
node.controller_odom_flag
), "ROSbot does not move properly in x direction. Check rosbot_base_controller!"
Expand All @@ -72,7 +75,10 @@ def test_diff_drive_simulation():
), "ROSbot does not move properly in x direction. Check ekf_filter_node!"

node.set_destination_speed(0.0, 0.0, 3.0)
assert node.vel_stabilization_time_event.wait(timeout=20.0), "Simulation crashed!"
assert node.vel_stabilization_time_event.wait(timeout=20.0), (
"The simulation is running slowly or has crashed! The time elapsed since setting the"
f" target speed is: {(node.current_time - node.goal_received_time):.1f}."
)
assert (
node.controller_odom_flag
), "ROSbot does not rotate properly. Check rosbot_base_controller!"
Expand Down
15 changes: 12 additions & 3 deletions rosbot_gazebo/test/test_mecanum_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,10 @@ def test_mecanum_simulation():
# 0.9 m/s and 3.0 rad/s are controller's limits defined in
# rosbot_controller/config/mecanum_drive_controller.yaml
node.set_destination_speed(0.9, 0.0, 0.0)
assert node.vel_stabilization_time_event.wait(timeout=20.0), "Simulation crashed!"
assert node.vel_stabilization_time_event.wait(timeout=20.0), (
"The simulation is running slowly or has crashed! The time elapsed since setting the"
f" target speed is: {(node.current_time - node.goal_received_time):.1f}."
)
assert (
node.controller_odom_flag
), "ROSbot does not move properly in x direction. Check rosbot_base_controller!"
Expand All @@ -72,7 +75,10 @@ def test_mecanum_simulation():
), "ROSbot does not move properly in x direction. Check ekf_filter_node!"

node.set_destination_speed(0.0, 0.9, 0.0)
assert node.vel_stabilization_time_event.wait(timeout=20.0), "Simulation crashed!"
assert node.vel_stabilization_time_event.wait(timeout=20.0), (
"The simulation is running slowly or has crashed! The time elapsed since setting the"
f" target speed is: {(node.current_time - node.goal_received_time):.1f}."
)
assert (
node.controller_odom_flag
), "ROSbot does not move properly in y direction. Check rosbot_base_controller!"
Expand All @@ -81,7 +87,10 @@ def test_mecanum_simulation():
), "ROSbot does not move properly in y direction. Check ekf_filter_node!"

node.set_destination_speed(0.0, 0.0, 3.0)
assert node.vel_stabilization_time_event.wait(timeout=20.0), "Simulation crashed!"
assert node.vel_stabilization_time_event.wait(timeout=20.0), (
"The simulation is running slowly or has crashed! The time elapsed since setting the"
f" target speed is: {(node.current_time - node.goal_received_time):.1f}."
)
assert (
node.controller_odom_flag
), "ROSbot does not rotate properly. Check rosbot_xl_base_controller!"
Expand Down
4 changes: 2 additions & 2 deletions rosbot_gazebo/test/test_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -117,8 +117,8 @@ def timer_callback(self):
self.publish_cmd_vel_messages()
self.lookup_transform_odom()

current_time_s = 1e-9 * self.get_clock().now().nanoseconds
if current_time_s > self.goal_received_time + self.VELOCITY_STABILIZATION_DELAY:
self.current_time = 1e-9 * self.get_clock().now().nanoseconds
if self.current_time > self.goal_received_time + self.VELOCITY_STABILIZATION_DELAY:
self.vel_stabilization_time_event.set()

def scan_callback(self, data: LaserScan):
Expand Down

0 comments on commit 3d1887b

Please sign in to comment.