Skip to content

Commit

Permalink
Add Kuba suggestions
Browse files Browse the repository at this point in the history
  • Loading branch information
rafal-gorecki committed Jan 30, 2024
1 parent 1fb0a56 commit 0501a5d
Show file tree
Hide file tree
Showing 7 changed files with 24 additions and 37 deletions.
4 changes: 0 additions & 4 deletions .github/workflows/industrial_ci.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
4 changes: 0 additions & 4 deletions rosbot_xl/rosbot_xl_hardware.repos
Original file line number Diff line number Diff line change
Expand Up @@ -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
5 changes: 0 additions & 5 deletions rosbot_xl/rosbot_xl_simulation.repos
Original file line number Diff line number Diff line change
@@ -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
Expand Down
12 changes: 6 additions & 6 deletions rosbot_xl_bringup/test/test_multirobot_ekf_and_scan.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down
12 changes: 6 additions & 6 deletions rosbot_xl_gazebo/test/test_multirobot_diff_drive_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down
12 changes: 6 additions & 6 deletions rosbot_xl_gazebo/test/test_multirobot_mecanum_simulation.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()

Expand Down
12 changes: 6 additions & 6 deletions rosbot_xl_gazebo/test/test_utils.py
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down Expand Up @@ -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()

Expand Down

0 comments on commit 0501a5d

Please sign in to comment.