Skip to content

Commit

Permalink
changed rosbot_xl_gazebo to ament_python | added lidar tests and gaze…
Browse files Browse the repository at this point in the history
…bo moving tests

Signed-off-by: Jakub Delicat <jakub.delicat@husarion.com>
  • Loading branch information
delihus committed Oct 19, 2023
1 parent 2f76033 commit ac634bc
Show file tree
Hide file tree
Showing 19 changed files with 840 additions and 23 deletions.
21 changes: 21 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,27 @@ source install/setup.bash
ros2 launch rosbot_xl_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:
```
colcon test-result --verbose
```

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

## Demos

For further usage examples check out our other repositories:
Expand Down
124 changes: 124 additions & 0 deletions rosbot_xl_bringup/test/bringup_test_node.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
# Copyright 2021 Open Source Robotics Foundation, Inc.
# Copyright 2023 Husarion
#
# 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.

import rclpy
import math

from threading import Event
from threading import Thread

from rclpy.node import Node

from sensor_msgs.msg import JointState, Imu, LaserScan
from tf2_ros import TransformException
from tf2_ros.buffer import Buffer
from tf2_ros.transform_listener import TransformListener


class BringupTestNode(Node):
ROSBOT_HARDWARE_PUBLISHERS_RATE = 10.0

__test__ = False

def __init__(self, name="test_node"):
super().__init__(name)
self.odom_tf_event = Event()
self.scan_filter_event = Event()

def create_test_subscribers_and_publishers(self):
self.imu_publisher = self.create_publisher(Imu, "_imu/data_raw", 10)

self.joint_states_publisher = self.create_publisher(
JointState, "_motors_response", 10
)

self.tf_buffer = Buffer()
self.tf_listener = TransformListener(self.tf_buffer, self)

self.scan_publisher = self.create_publisher(LaserScan, "scan", 10)
self.filtered_scan_subscriber = self.create_subscription(
LaserScan, "scan_filtered", self.filtered_scan_callback, 10
)

self.timer = None

def lookup_transform_odom(self):
try:
self.tf_buffer.lookup_transform("odom", "base_link", rclpy.time.Time())
self.odom_tf_event.set()
except TransformException as ex:
self.get_logger().error(f"Could not transform odom to base_link: {ex}")

def start_node_thread(self):
self.ros_spin_thread = Thread(
target=lambda node: rclpy.spin(node), args=(self,)
)
self.ros_spin_thread.start()

def start_publishing_fake_hardware(self):
self.timer = self.create_timer(
1.0 / self.ROSBOT_HARDWARE_PUBLISHERS_RATE,
self.timer_callback,
)

def filtered_scan_callback(self, msg):
if msg.ranges[0] == 5.0 and msg.ranges[-1] == 5.0:
for i in range(len(msg.ranges) - 2):
# when is not .nan
if not math.isnan(msg.ranges[i + 1]):
return

self.scan_filter_event.set()

def timer_callback(self):
self.publish_fake_hardware_messages()
self.lookup_transform_odom()
self.publish_scan()

def publish_fake_hardware_messages(self):
imu_msg = Imu()
imu_msg.header.stamp = self.get_clock().now().to_msg()
imu_msg.header.frame_id = "imu_link"

joint_state_msg = JointState()
joint_state_msg.header.stamp = self.get_clock().now().to_msg()
joint_state_msg.name = [
"fl_wheel_joint",
"fr_wheel_joint",
"rl_wheel_joint",
"rr_wheel_joint",
]
joint_state_msg.position = [0.0, 0.0, 0.0, 0.0]
joint_state_msg.velocity = [0.0, 0.0, 0.0, 0.0]

self.imu_publisher.publish(imu_msg)
self.joint_states_publisher.publish(joint_state_msg)

def publish_scan(self):
msg = LaserScan()
msg.header.frame_id = "base_link"
msg.angle_min = 0.0
msg.angle_max = 2.0 * 3.14159265
msg.angle_increment = 0.05
msg.time_increment = 0.1
msg.scan_time = 0.1
msg.range_min = 0.0
msg.range_max = 10.0

# All points inside filtered box
msg.ranges = [0.1] * 126
msg.ranges[0] = 5.0
msg.ranges[-1] = 5.0
self.scan_publisher.publish(msg)
2 changes: 1 addition & 1 deletion rosbot_xl_description/urdf/wheel.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@
<child link="${prefix}_wheel_link" />
<origin xyz="${x} ${y} 0.0" rpy="0.0 0.0 0.0" />
<axis xyz="0.0 1.0 0.0" />
<limit effort="1.27" velocity="21.0" />
<limit effort="1.5" velocity="30.0" />
<dynamics damping="0.001" friction="0.001" />
</joint>

Expand Down
11 changes: 0 additions & 11 deletions rosbot_xl_gazebo/CMakeLists.txt

This file was deleted.

51 changes: 44 additions & 7 deletions rosbot_xl_gazebo/launch/simulation.launch.py
Original file line number Diff line number Diff line change
@@ -1,4 +1,16 @@
#!/usr/bin/env python3
# Copyright 2023 Husarion
#
# 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.

from launch import LaunchDescription
from launch.actions import (
Expand All @@ -7,6 +19,7 @@
)
from launch.substitutions import (
PathJoinSubstitution,
PythonExpression,
LaunchConfiguration,
)
from launch.launch_description_sources import PythonLaunchDescriptionSource
Expand All @@ -21,7 +34,10 @@ def generate_launch_description():
declare_mecanum_arg = DeclareLaunchArgument(
"mecanum",
default_value="False",
description="Whether to use mecanum drive controller (otherwise diff drive controller is used)",
description=(
"Whether to use mecanum drive controller"
"(otherwise diff drive controller is used)"
),
)

lidar_model = LaunchConfiguration("lidar_model")
Expand All @@ -45,12 +61,28 @@ def generate_launch_description():
description="Whether to include camera mount to the robot URDF",
)

map_package = get_package_share_directory("husarion_office_gz")
world_file = PathJoinSubstitution([map_package, "worlds", "husarion_world.sdf"])
world_package = get_package_share_directory("husarion_office_gz")
world_file = PathJoinSubstitution([world_package, "worlds", "husarion_world.sdf"])
world_cfg = LaunchConfiguration("world")
declare_world_arg = DeclareLaunchArgument(
"world", default_value=["-r ", world_file], description="SDF world file"
"world", default_value=world_file, description="SDF world file"
)

headless = LaunchConfiguration("headless")
declare_headless_arg = DeclareLaunchArgument(
"headless",
default_value="False",
description=("Run Gazebo Ignition in the headless mode"),
)

headless_cfg = PythonExpression(
[
"'--headless-rendering -s -r' if ",
headless,
" else '-r'",
]
)
gz_args = [headless_cfg, " ", world_cfg]

gz_sim = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
Expand All @@ -62,7 +94,10 @@ def generate_launch_description():
]
)
),
launch_arguments={"gz_args": world_cfg}.items(),
launch_arguments={
"gz_args": gz_args,
"on_exit_shutdown": "True",
}.items(),
)

gz_spawn_entity = Node(
Expand Down Expand Up @@ -143,7 +178,9 @@ def generate_launch_description():
declare_camera_model_arg,
declare_include_camera_mount_arg,
declare_world_arg,
# Sets use_sim_time for all nodes started below (doesn't work for nodes started from ignition gazebo)
declare_headless_arg,
# Sets use_sim_time for all nodes started below
# (doesn't work for nodes started from ignition gazebo)
SetParameter(name="use_sim_time", value=True),
gz_sim,
ign_bridge,
Expand Down
19 changes: 15 additions & 4 deletions rosbot_xl_gazebo/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,19 +4,18 @@
<name>rosbot_xl_gazebo</name>
<version>0.8.2</version>

<description>The rosbot_xl_gazebo package</description>
<description>Gazebo Ignition simulation for ROSbot XL</description>
<license>Apache License 2.0</license>

<author email="maciej.stepien@husarion.com">Maciej Stępień</author>
<author email="krzysztof.wojciechowski@husarion.com">Krzysztof Wojciechowski</author>
<author email="jakub.delicat@husarion.com">Jakub Delicat</author>
<maintainer email="support@husarion.com">Husarion</maintainer>

<url type="website">https://husarion.com/</url>
<url type="repository">https://github.com/husarion/rosbot_xl_ros</url>
<url type="bugtracker">https://github.com/husarion/rosbot_xl_ros/issues</url>

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>rosbot_xl_bringup</exec_depend>

<exec_depend>launch</exec_depend>
Expand All @@ -30,7 +29,19 @@
<exec_depend>ros_gz_bridge</exec_depend>
<exec_depend>ign_ros2_control</exec_depend>

<test_depend>python3-pytest</test_depend>
<test_depend>launch</test_depend>
<test_depend>launch_ros</test_depend>
<test_depend>launch_pytest</test_depend>

<test_depend>tf_transformations</test_depend>
<test_depend>python-transforms3d-pip</test_depend>
<test_depend>nav_msgs</test_depend>
<test_depend>geometry_msgs</test_depend>

<test_depend>rosbot_bringup</test_depend>

<export>
<build_type>ament_cmake</build_type>
<build_type>ament_python</build_type>
</export>
</package>
Empty file.
4 changes: 4 additions & 0 deletions rosbot_xl_gazebo/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/rosbot_xl_gazebo
[install]
install_scripts=$base/lib/rosbot_xl_gazebo
26 changes: 26 additions & 0 deletions rosbot_xl_gazebo/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
import os
from glob import glob
from setuptools import find_packages, setup

package_name = "rosbot_xl_gazebo"

setup(
name=package_name,
version="0.8.2",
packages=find_packages(exclude=["test"]),
data_files=[
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
("share/" + package_name, ["package.xml"]),
(os.path.join("share", package_name, "launch"), glob("launch/*.launch.py")),
],
install_requires=["setuptools"],
zip_safe=True,
maintainer="Husarion",
maintainer_email="contact@husarion.com",
description="Gazebo Ignition simulation for ROSbot XL",
license="Apache License 2.0",
tests_require=["pytest"],
entry_points={
"console_scripts": [],
},
)
38 changes: 38 additions & 0 deletions rosbot_xl_gazebo/test/kill_ign.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,38 @@
# Copyright 2023 Husarion
#
# 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.

import subprocess

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


def kill_ign_linux_processes():
try:
result = subprocess.run(
["pgrep", "-f", "ign gazebo"],
capture_output=True,
text=True,
check=True,
)

pids = result.stdout.strip().split("\n")
for pid in pids:
subprocess.run(["kill", pid], check=True)
print("Killed all Ignition Gazebo processes")
except subprocess.CalledProcessError as e:
print(e)


kill_ign_linux_processes()
Loading

0 comments on commit ac634bc

Please sign in to comment.