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

Test gazebo scan #71

Merged
merged 7 commits into from
Oct 16, 2023
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
21 changes: 21 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,27 @@ source install/setup.bash
ros2 launch rosbot_gazebo simulation.launch.py
```

## Testing package

### Industrial CI
```
colcon test
```

> [!NOTE]
> Command `colcon test` does not build the code. Remember to build your code after changes.

If tests finish with errors print logs:
delihus marked this conversation as resolved.
Show resolved Hide resolved
```
colcon test-result --verbose
```

### Format python code with [Black](https://github.com/psf/black)
```
cd src/
black rosbot*
```

## Demo
Bellow you can find demos with ROSbots:
- in [rosbot-docker](https://github.com/husarion/rosbot-docker/tree/ros2) you will find a simple example how to drive ROSbot with `teleop_twist_keyboard`.
Expand Down
9 changes: 9 additions & 0 deletions rosbot_gazebo/test/simulation_test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,7 @@

from geometry_msgs.msg import Twist
from nav_msgs.msg import Odometry
from sensor_msgs.msg import LaserScan

from tf2_ros import TransformException
from tf2_ros.buffer import Buffer
Expand All @@ -43,6 +44,7 @@ def __init__(self, name="test_node"):
self.goal_y_event = Event()
self.goal_yaw_event = Event()
self.odom_tf_event = Event()
self.scan_event = Event()

def clear_events(self):
self.goal_x_event.clear()
Expand All @@ -62,6 +64,9 @@ def create_test_subscribers_and_publishers(self):
Odometry, "/odometry/filtered", self.odometry_callback, 10
)

self.scan_sub = self.create_subscription(
LaserScan, "/scan", self.scan_callback, 10
)
self.tf_buffer = Buffer()
self.tf_listener = TransformListener(self.tf_buffer, self)

Expand Down Expand Up @@ -97,6 +102,10 @@ def timer_callback(self):
self.publish_cmd_vel_messages()
self.lookup_transform_odom()

def scan_callback(self, data: LaserScan):
if data.ranges:
self.scan_event.set()

def publish_cmd_vel_messages(self):
twist_msg = Twist()

Expand Down
3 changes: 3 additions & 0 deletions rosbot_gazebo/test/test_diff_drive_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -72,6 +72,9 @@ def test_diff_drive_simulation():
msgs_received_flag = node.goal_yaw_event.wait(timeout=60.0)
assert msgs_received_flag, "ROSbot does not rotate properly!"

msgs_received_flag = node.scan_event.wait(timeout=60.0)
assert msgs_received_flag, "ROSbot's lidar does not work properly!"

finally:
# The pytest cannot kill properly the Gazebo Ignition's tasks what blocks launching
# several tests in a row.
Expand Down
3 changes: 3 additions & 0 deletions rosbot_gazebo/test/test_mecanum_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -77,6 +77,9 @@ def test_mecanum_simulation():
msgs_received_flag = node.goal_yaw_event.wait(timeout=60.0)
assert msgs_received_flag, "ROSbot does not rotate properly!"

msgs_received_flag = node.scan_event.wait(timeout=60.0)
assert msgs_received_flag, "ROSbot's lidar does not work properly!"

finally:
# The pytest cannot kill properly the Gazebo Ignition's tasks what blocks launching
# several tests in a row.
Expand Down
Loading