ROS Bridge Update

This commit is contained in:
2026-01-02 06:50:31 +00:00
parent 1bbd9c8377
commit 924d803e71
4 changed files with 60 additions and 137 deletions

View File

@@ -8,8 +8,6 @@ Controls rover movement via Gazebo pose commands.
import base64
import json
import math
import subprocess
import threading
from typing import Optional, Dict, Any
import numpy as np
@@ -44,11 +42,6 @@ class GazeboBridge(Node):
self._drone_pos = [0.0, 0.0, 5.0]
self._drone_orn = [0.0, 0.0, 0.0, 1.0]
# Detect gz vs ign command
import shutil
self._gz_cmd = 'gz' if shutil.which('gz') else 'ign'
self.get_logger().info(f' Using Gazebo command: {self._gz_cmd}')
sensor_qos = QoSProfile(
reliability=ReliabilityPolicy.BEST_EFFORT,
depth=10
@@ -95,57 +88,23 @@ class GazeboBridge(Node):
self._gz_cmd_vel_pub.publish(gz_msg)
def _rover_callback(self, msg: String) -> None:
"""Receive rover position and update in Gazebo."""
"""Receive rover position (for telemetry only - rover is static in Gazebo)."""
try:
data = json.loads(msg.data)
pos = data.get('position', {})
new_pos = [
self._rover_pos = [
pos.get('x', 0.0),
pos.get('y', 0.0),
pos.get('z', 0.15)
]
# Only update if position changed significantly
if (abs(new_pos[0] - self._rover_pos[0]) > 0.01 or
abs(new_pos[1] - self._rover_pos[1]) > 0.01):
self._rover_pos = new_pos
# Move rover in Gazebo (async to avoid blocking)
threading.Thread(target=self._move_rover_in_gazebo, daemon=True).start()
# Note: In Gazebo mode, rover position is tracked but the visual
# model stays static. Moving the model requires the set_pose service
# which has networking issues in WSL2. For moving rover tests,
# use PyBullet (standalone_simulation.py or simulation_host.py).
except json.JSONDecodeError:
pass
def _move_rover_in_gazebo(self) -> None:
"""Send pose command to Gazebo to move the landing pad."""
try:
x, y, z = self._rover_pos
# Use Gazebo service to set model pose
if self._gz_cmd == 'ign':
# Ignition Gazebo (Fortress)
cmd = [
'ign', 'service', '-s', '/world/drone_landing_world/set_pose',
'--reqtype', 'ignition.msgs.Pose',
'--reptype', 'ignition.msgs.Boolean',
'--timeout', '100',
'--req', f'name: "landing_pad", position: {{x: {x}, y: {y}, z: {z}}}'
]
else:
# Newer Gazebo
cmd = [
'gz', 'service', '-s', '/world/drone_landing_world/set_pose',
'--reqtype', 'gz.msgs.Pose',
'--reptype', 'gz.msgs.Boolean',
'--timeout', '100',
'--req', f'name: "landing_pad", position: {{x: {x}, y: {y}, z: {z}}}'
]
subprocess.run(cmd, capture_output=True, timeout=1.0)
except subprocess.TimeoutExpired:
pass
except Exception as e:
pass # Silently ignore errors to avoid spam
def _camera_callback(self, msg: Image) -> None:
"""Process camera images and encode as base64."""