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 #70

Merged
merged 37 commits into from
Oct 11, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
37 commits
Select commit Hold shift + click to select a range
7bffd1e
rosbot_gazebo: added tests | changed to ament_python
delihus Sep 1, 2023
8333c48
added headless argument to simulation.launch.py
delihus Sep 4, 2023
3ffde6a
Merge remote-tracking branch 'origin/humble' into test-gazebo
delihus Sep 4, 2023
f0935c5
added mecanum and diff drive movement test
delihus Sep 4, 2023
6e89fc5
added python-transforms3d-pip to test_depend
delihus Sep 4, 2023
4784d4d
added logs for odom callback rosbot_gazebo tests
delihus Sep 4, 2023
7a0ca22
changed names for rosbot_gazebo tests
delihus Sep 4, 2023
d6a6279
print rpy rosbot_gazebo
delihus Sep 4, 2023
d3dd76e
changed goal angle for rosbot_gazebo tests
delihus Sep 4, 2023
94efebf
changed goal angle for rosbot_gazebo tests
delihus Sep 4, 2023
bb51284
rosbot_gazebo tests only one test
delihus Sep 5, 2023
233d7c4
rosbot_gazebo tests only one test
delihus Sep 5, 2023
bb126fb
rosbot_gazebo tests only one test
delihus Sep 5, 2023
4210483
rosbot_gazebo tests only one test
delihus Sep 5, 2023
d626a30
rosbot_gazebo tests only one test
delihus Sep 5, 2023
b590d78
rosbot_gazebo tests only one test
delihus Sep 5, 2023
1a68ca6
rosbot_gazebo tests only one test
delihus Sep 5, 2023
a3fc04d
rosbot_gazebo tests only one test
delihus Sep 5, 2023
a3886b7
changed goal angle for rosbot_gazebo tests
delihus Sep 5, 2023
fc67118
changed goal angle for rosbot_gazebo tests
delihus Sep 5, 2023
d3a0321
apply black format
delihus Sep 5, 2023
65f71c4
Merge branch 'humble' into test-gazebo
rafal-gorecki Sep 21, 2023
c8acc7d
refactor
rafal-gorecki Sep 21, 2023
afb71a0
added scale and velocities variables
delihus Sep 21, 2023
261a129
Merge remote-tracking branch 'origin/test-gazebo' into test-gazebo
delihus Sep 21, 2023
bfe04fe
updated names
delihus Sep 26, 2023
55c862b
Added ignition kill script
delihus Oct 9, 2023
d5efbad
Added diff drive test for rosbot_gazebo
delihus Oct 9, 2023
34e7529
Removed spell error
delihus Oct 9, 2023
41a6813
headless mode in mecanum
delihus Oct 10, 2023
17f9427
fixed killing ignition
delihus Oct 10, 2023
ebf514e
rafal-sugestions
rafal-gorecki Oct 10, 2023
92bd0a7
Merge pull request #74 from husarion/rafal-suggestions
delihus Oct 11, 2023
9dde480
changed max vel wheel joint | changed testing velocities to the maxim…
delihus Oct 11, 2023
1d9e7df
changed to headless mode
delihus Oct 11, 2023
3b441ae
changed odom topic to tf
delihus Oct 11, 2023
e109f9e
changed rosbot_gazebo tf timeout
delihus Oct 11, 2023
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
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ log
rosbot_hardware_interfaces/
ros_components_description/
rosbot_controllers/
husarion/gazebo_worlds
husarion/husarion_office_gz
gazebosim/gz_ros2_control

# pyspelling
Expand Down
4 changes: 2 additions & 2 deletions rosbot_bringup/config/ekf.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ ekf_filter_node:
imu0_differential: false
imu0_relative: true
imu0_remove_gravitational_acceleration: true

# [ADVANCED] The process noise covariance matrix can be difficult to tune, and can vary for each application, so it is
# exposed as a configuration parameter. This matrix represents the noise we add to the total error after each
# prediction step. The better the omnidirectional motion model matches your system, the smaller these values can be.
Expand Down Expand Up @@ -73,7 +73,7 @@ ekf_filter_node:
0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 1e-8, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1e-9, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,
Expand Down
28 changes: 19 additions & 9 deletions rosbot_bringup/test/bringup_test_node.py
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,9 @@
from rclpy.node import Node

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


class BringupTestNode(Node):
Expand All @@ -31,7 +33,7 @@ class BringupTestNode(Node):

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

def create_test_subscribers_and_publishers(self):
self.imu_publisher = self.create_publisher(Imu, "_imu/data_raw", 10)
Expand All @@ -40,26 +42,34 @@ def create_test_subscribers_and_publishers(self):
JointState, "_motors_response", 10
)

self.odom_sub = self.create_subscription(
Odometry, "/odometry/filtered", self.odometry_callback, 10
)
self.tf_buffer = Buffer()
self.tf_listener = TransformListener(self.tf_buffer, self)

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 odometry_callback(self, data):
self.odom_msg_event.set()

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

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

def publish_fake_hardware_messages(self):
imu_msg = Imu()
imu_msg.header.stamp = self.get_clock().now().to_msg()
Expand Down
4 changes: 2 additions & 2 deletions rosbot_bringup/test/test_diff_drive_ekf.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,10 +58,10 @@ def test_bringup_startup_success():
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
msgs_received_flag = node.odom_tf_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Odom message but it was not received. Check robot_localization!"
), "Expected odom to base_link tf but it was not received. Check robot_localization!"

finally:
rclpy.shutdown()
5 changes: 3 additions & 2 deletions rosbot_bringup/test/test_mecanum_ekf.py
Original file line number Diff line number Diff line change
Expand Up @@ -58,9 +58,10 @@ def test_bringup_startup_success():
node.start_publishing_fake_hardware()

node.start_node_thread()
msgs_received_flag = node.odom_msg_event.wait(timeout=10.0)
msgs_received_flag = node.odom_tf_event.wait(timeout=10.0)
assert (
msgs_received_flag
), "Expected Odom message but it was not received. Check robot_localization!"
), "Expected odom to base_link tf but it was not received. Check robot_localization!"

finally:
rclpy.shutdown()
2 changes: 1 addition & 1 deletion rosbot_description/urdf/wheel.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,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.5" velocity="5.0" />
<limit effort="1.5" velocity="24.0" />
<dynamics damping="0.001" friction="0.001" />
</joint>

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

This file was deleted.

78 changes: 57 additions & 21 deletions rosbot_gazebo/launch/simulation.launch.py
Original file line number Diff line number Diff line change
@@ -1,10 +1,25 @@
# 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 (
IncludeLaunchDescription,
DeclareLaunchArgument,
)
from launch.substitutions import (
PathJoinSubstitution,
PythonExpression,
LaunchConfiguration,
)
from launch.launch_description_sources import PythonLaunchDescriptionSource
Expand All @@ -19,15 +34,34 @@ 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)"
),
)

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]

use_gpu = LaunchConfiguration("use_gpu")
declare_use_gpu_arg = DeclareLaunchArgument(
Expand All @@ -46,7 +80,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 All @@ -68,26 +105,23 @@ def generate_launch_description():
],
output="screen",
)

ign_bridge = Node(
package="ros_gz_bridge",
executable="parameter_bridge",
name="ros_gz_bridge",
arguments=[
"/scan" + "@sensor_msgs/msg/LaserScan" + "[ignition.msgs.LaserScan",
"/camera/camera_info"
+ "@sensor_msgs/msg/CameraInfo"
+ "[ignition.msgs.CameraInfo",
"/camera/depth_image" + "@sensor_msgs/msg/Image" + "[ignition.msgs.Image",
"/camera/image" + "@sensor_msgs/msg/Image" + "[ignition.msgs.Image",
"/camera/points"
+ "@sensor_msgs/msg/PointCloud2"
+ "[ignition.msgs.PointCloudPacked",
"/clock" + "@rosgraph_msgs/msg/Clock" + "[ignition.msgs.Clock",
# an IR sensor or a sonar are not implemented yet https://github.com/gazebosim/gz-sensors/issues/19
"/range/fl" + "@sensor_msgs/msg/LaserScan" + "[ignition.msgs.LaserScan",
"/range/fr" + "@sensor_msgs/msg/LaserScan" + "[ignition.msgs.LaserScan",
"/range/rl" + "@sensor_msgs/msg/LaserScan" + "[ignition.msgs.LaserScan",
"/range/rr" + "@sensor_msgs/msg/LaserScan" + "[ignition.msgs.LaserScan",
"/scan@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/camera/camera_info@sensor_msgs/msg/CameraInfo[ignition.msgs.CameraInfo",
"/camera/depth_image@sensor_msgs/msg/Image[ignition.msgs.Image",
"/camera/image@sensor_msgs/msg/Image[ignition.msgs.Image",
"/camera/points@sensor_msgs/msg/PointCloud2[ignition.msgs.PointCloudPacked",
"/clock@rosgraph_msgs/msg/Clock[ignition.msgs.Clock",
# an IR sensor is not implemented yet https://github.com/gazebosim/gz-sensors/issues/19
"/range/fl@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/range/fr@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/range/rl@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
"/range/rr@sensor_msgs/msg/LaserScan[ignition.msgs.LaserScan",
],
remappings=[
("/camera/camera_info", "/camera/color/camera_info"),
Expand Down Expand Up @@ -139,8 +173,10 @@ def generate_launch_description():
[
declare_mecanum_arg,
declare_world_arg,
declare_headless_arg,
declare_use_gpu_arg,
# Sets use_sim_time for all nodes started below (doesn't work for nodes started from ignition gazebo)
# 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
16 changes: 12 additions & 4 deletions rosbot_gazebo/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<name>rosbot_gazebo</name>
<version>0.8.4</version>

<description>The rosbot_gazebo package</description>
<description>Gazebo Ignition simulation for ROSbot 2, 2R, PRO</description>
<license>Apache License 2.0</license>

<author email="[email protected]">Krzysztof Wojciechowski</author>
Expand All @@ -14,8 +14,6 @@
<url type="repository">https://github.com/husarion/rosbot_ros</url>
<url type="bugtracker">https://github.com/husarion/rosbot_ros/issues</url>

<buildtool_depend>ament_cmake</buildtool_depend>

<exec_depend>rosbot_bringup</exec_depend>

<exec_depend>launch</exec_depend>
Expand All @@ -29,7 +27,17 @@
<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>

<export>
<build_type>ament_cmake</build_type>
<build_type>ament_python</build_type>
</export>
</package>
Empty file.
4 changes: 4 additions & 0 deletions rosbot_gazebo/setup.cfg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
[develop]
script_dir=$base/lib/rosbot_gazebo
[install]
install_scripts=$base/lib/rosbot_gazebo
26 changes: 26 additions & 0 deletions rosbot_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_gazebo"

setup(
name=package_name,
version="0.8.0",
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="[email protected]",
description="Gazebo Ignition simulation for ROSbot 2, 2R, PRO",
license="Apache License 2.0",
tests_require=["pytest"],
entry_points={
"console_scripts": [],
},
)
38 changes: 38 additions & 0 deletions rosbot_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
Loading