From 0501a5d624671bedc5b0661d91323adfe120abee Mon Sep 17 00:00:00 2001 From: rafal-gorecki Date: Tue, 30 Jan 2024 09:11:42 +0100 Subject: [PATCH] Add Kuba suggestions --- .github/workflows/industrial_ci.yaml | 4 ---- rosbot_xl/rosbot_xl_hardware.repos | 4 ---- rosbot_xl/rosbot_xl_simulation.repos | 5 ----- .../test/test_multirobot_ekf_and_scan.py | 12 ++++++------ .../test/test_multirobot_diff_drive_simulation.py | 12 ++++++------ .../test/test_multirobot_mecanum_simulation.py | 12 ++++++------ rosbot_xl_gazebo/test/test_utils.py | 12 ++++++------ 7 files changed, 24 insertions(+), 37 deletions(-) diff --git a/.github/workflows/industrial_ci.yaml b/.github/workflows/industrial_ci.yaml index 918d606..29bb70c 100644 --- a/.github/workflows/industrial_ci.yaml +++ b/.github/workflows/industrial_ci.yaml @@ -49,10 +49,6 @@ jobs: cp -r src/ros2_controllers/diff_drive_controller src/ cp -r src/ros2_controllers/imu_sensor_broadcaster src/ rm -rf src/ros2_controllers - cp -r src/geometry2/tf2_ros_py src/ - rm -rf src/geometry2/ - rm -rf src/gazebosim/gz_ros2_control/ign_ros2_control_demos - rm -rf src/gazebosim/gz_ros2_control/gz_ros2_control_tests - uses: ros-industrial/industrial_ci@master env: diff --git a/rosbot_xl/rosbot_xl_hardware.repos b/rosbot_xl/rosbot_xl_hardware.repos index 3f0cd08..8468f70 100644 --- a/rosbot_xl/rosbot_xl_hardware.repos +++ b/rosbot_xl/rosbot_xl_hardware.repos @@ -15,7 +15,3 @@ repositories: type: git url: https://github.com/delihus/ros2_controllers version: humble - geometry2: - type: git - url: https://github.com/delihus/geometry2 - version: rolling diff --git a/rosbot_xl/rosbot_xl_simulation.repos b/rosbot_xl/rosbot_xl_simulation.repos index 40ba729..e4d80df 100644 --- a/rosbot_xl/rosbot_xl_simulation.repos +++ b/rosbot_xl/rosbot_xl_simulation.repos @@ -1,9 +1,4 @@ repositories: - gazebosim/gz_ros2_control: - type: git - url: https://github.com/ros-controls/gz_ros2_control - version: humble - husarion/husarion_office_gz: type: git url: https://github.com/husarion/husarion_office_gz diff --git a/rosbot_xl_bringup/test/test_multirobot_ekf_and_scan.py b/rosbot_xl_bringup/test/test_multirobot_ekf_and_scan.py index cc09a12..a25f390 100644 --- a/rosbot_xl_bringup/test/test_multirobot_ekf_and_scan.py +++ b/rosbot_xl_bringup/test/test_multirobot_ekf_and_scan.py @@ -65,17 +65,17 @@ def test_namespaced_bringup_startup_success(): nodes = {} executor = SingleThreadedExecutor() - for node_name in robot_names: - node = BringupTestNode("test_bringup", namespace=node_name) + for node_namespace in robot_names: + node = BringupTestNode("test_bringup", namespace=node_namespace) node.start_publishing_fake_hardware() - nodes[node_name] = node + nodes[node_namespace] = node executor.add_node(node) Thread(target=lambda executor: executor.spin(), args=(executor,)).start() - for node_name in robot_names: - node = nodes[node_name] - ekf_and_scan_test(node, node_name) + for node_namespace in robot_names: + node = nodes[node_namespace] + ekf_and_scan_test(node, node_namespace) executor.remove_node(node) node.destroy_node() diff --git a/rosbot_xl_gazebo/test/test_multirobot_diff_drive_simulation.py b/rosbot_xl_gazebo/test/test_multirobot_diff_drive_simulation.py index 0b7d9f5..c6a760e 100644 --- a/rosbot_xl_gazebo/test/test_multirobot_diff_drive_simulation.py +++ b/rosbot_xl_gazebo/test/test_multirobot_diff_drive_simulation.py @@ -67,16 +67,16 @@ def test_multirobot_diff_drive_simulation(): nodes = {} executor = SingleThreadedExecutor() - for node_name in robots: - node = SimulationTest("test_multirobot_diff_drive_simulation", namespace=node_name) - nodes[node_name] = node + for node_namespace in robots: + node = SimulationTest("test_multirobot_diff_drive_simulation", namespace=node_namespace) + nodes[node_namespace] = node executor.add_node(node) Thread(target=lambda executor: executor.spin(), args=(executor,)).start() - for node_name in robots: - node = nodes[node_name] - diff_test(node, node_name) + for node_namespace in robots: + node = nodes[node_namespace] + diff_test(node, node_namespace) executor.remove_node(node) node.destroy_node() diff --git a/rosbot_xl_gazebo/test/test_multirobot_mecanum_simulation.py b/rosbot_xl_gazebo/test/test_multirobot_mecanum_simulation.py index 12025f7..0d6ee47 100644 --- a/rosbot_xl_gazebo/test/test_multirobot_mecanum_simulation.py +++ b/rosbot_xl_gazebo/test/test_multirobot_mecanum_simulation.py @@ -68,16 +68,16 @@ def test_multirobot_mecanum_simulation(): nodes = {} executor = SingleThreadedExecutor() - for node_name in robots: - node = SimulationTest("test_multirobot_mecanum_simulation", namespace=node_name) - nodes[node_name] = node + for node_namespace in robots: + node = SimulationTest("test_multirobot_mecanum_simulation", namespace=node_namespace) + nodes[node_namespace] = node executor.add_node(node) Thread(target=lambda executor: executor.spin(), args=(executor,)).start() - for node_name in robots: - node = nodes[node_name] - mecanum_test(node, node_name) + for node_namespace in robots: + node = nodes[node_namespace] + mecanum_test(node, node_namespace) executor.remove_node(node) node.destroy_node() diff --git a/rosbot_xl_gazebo/test/test_utils.py b/rosbot_xl_gazebo/test/test_utils.py index 19ee642..d39c5e5 100644 --- a/rosbot_xl_gazebo/test/test_utils.py +++ b/rosbot_xl_gazebo/test/test_utils.py @@ -50,22 +50,22 @@ def __init__(self, name="test_node", namespace=None): # Sensor callback self.camera_rgb_sub = self.create_subscription( - Image, "camera/image", self.camera_rgb_callback, 10 + Image, "camera/image", self.camera_image_callback, 10 ) self.camera_pc_sub = self.create_subscription( - PointCloud2, "camera/points", self.camera_pc_callback, 10 + PointCloud2, "camera/points", self.camera_points_callback, 10 ) self.scan_sub = self.create_subscription(LaserScan, "scan", self.scan_callback, 10) # Timer - send cmd_vel and check if the time needed for speed stabilization has elapsed self.timer = self.create_timer(0.1, self.timer_callback) - # Values for cmd_vel + # Destination velocity for cmd_vel self.v_x = 0.0 self.v_y = 0.0 self.v_yaw = 0.0 - # Debug value + # Debug values self.controller_twist = None self.ekf_twist = None @@ -163,11 +163,11 @@ def scan_callback(self, data: LaserScan): if data.ranges: self.scan_event.set() - def camera_rgb_callback(self, data: Image): + def camera_image_callback(self, data: Image): if data.data: self.camera_color_event.set() - def camera_pc_callback(self, data: PointCloud2): + def camera_points_callback(self, data: PointCloud2): if data.data: self.camera_points_event.set()