|
|
|
|
@ -27,6 +27,7 @@ from rclpy.executors import MultiThreadedExecutor
|
|
|
|
|
import std_msgs.msg
|
|
|
|
|
import sensor_msgs.msg
|
|
|
|
|
import geometry_msgs.msg
|
|
|
|
|
import nav_msgs.msg
|
|
|
|
|
import mavros_msgs.msg
|
|
|
|
|
|
|
|
|
|
# ROS2 Service imports
|
|
|
|
|
@ -59,13 +60,14 @@ class PublishRateController:
|
|
|
|
|
# 注意 這邊是定義區 不要把參數寫在這裡 所以預設全部關閉
|
|
|
|
|
# 以這個專案 請看 mainOrchestrator.py 的 Orchestrator 初始化階段
|
|
|
|
|
self.topic_intervals = {
|
|
|
|
|
'position': 0.0, # GPS位置
|
|
|
|
|
'attitude': 0.0, # 姿態
|
|
|
|
|
'velocity': 0.0, # 速度
|
|
|
|
|
'position': 0.0, # GNSS位置
|
|
|
|
|
'position_ned': 0.0, # LOCAL_POSITION_NED (位置+速度)
|
|
|
|
|
'attitude': 0.0, # 姿態 (pitch yaw row 與其加速狀態)
|
|
|
|
|
'velocity': 0.0, # 速度 (已經包含在 vfr_hud 未來移除)
|
|
|
|
|
'battery': 0.0, # 電池
|
|
|
|
|
'vfr_hud': 0.0, # VFR HUD
|
|
|
|
|
'mode': 0.0, # 飛行模式
|
|
|
|
|
'summary': 0.0, # 載具摘要
|
|
|
|
|
'vfr_hud': 0.0, # VFR HUD (地速 空速 絕對高度 爬升率 航向 油門)
|
|
|
|
|
'mode': 0.0, # 飛行模式 (已經在 summary 裡 未來移除)
|
|
|
|
|
'summary': 0.0, # 載具摘要 (sysid 飛行模式 解鎖上鎖 gps狀態)
|
|
|
|
|
# 在這裡新增更多 topics...
|
|
|
|
|
}
|
|
|
|
|
# 記錄每個 topic 的最後發布時間 {(sysid, topic): timestamp}
|
|
|
|
|
@ -169,6 +171,7 @@ class VehicleStatusPublisher(Node):
|
|
|
|
|
# ═══════════════════════════════════════════════════════════════
|
|
|
|
|
# 發布各種狀態(通過頻率控制器判斷是否發布)
|
|
|
|
|
self._publish_position(sysid, status)
|
|
|
|
|
self._publish_position_ned(sysid, status)
|
|
|
|
|
self._publish_attitude(sysid, status)
|
|
|
|
|
self._publish_velocity(sysid, status)
|
|
|
|
|
self._publish_battery(sysid, status)
|
|
|
|
|
@ -224,6 +227,42 @@ class VehicleStatusPublisher(Node):
|
|
|
|
|
msg.status.status = gps.fix_type - 1 # MAVLink fix_type 轉 NavSatStatus
|
|
|
|
|
|
|
|
|
|
publisher.publish(msg)
|
|
|
|
|
|
|
|
|
|
def _publish_position_ned(self, sysid: int, status: mvv.ComponentStatus):
|
|
|
|
|
"""發布 LOCAL_POSITION_NED(NED 座標,含位置與速度)"""
|
|
|
|
|
if not self.rate_controller.should_publish(sysid, 'position_ned'):
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
local_pos = status.custom_status.get('local_position')
|
|
|
|
|
if not local_pos:
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
required_keys = ('x', 'y', 'z', 'vx', 'vy', 'vz')
|
|
|
|
|
if any(local_pos.get(k) is None for k in required_keys):
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
publisher = self._get_or_create_publisher(
|
|
|
|
|
sysid, 'position_ned', nav_msgs.msg.Odometry
|
|
|
|
|
)
|
|
|
|
|
|
|
|
|
|
if publisher.get_subscription_count() == 0:
|
|
|
|
|
return
|
|
|
|
|
|
|
|
|
|
msg = nav_msgs.msg.Odometry()
|
|
|
|
|
msg.header.stamp = self.get_clock().now().to_msg()
|
|
|
|
|
msg.header.frame_id = 'local_ned'
|
|
|
|
|
msg.child_frame_id = 'base_link_ned'
|
|
|
|
|
|
|
|
|
|
# 保持 MAVLink LOCAL_POSITION_NED 座標定義,不進行 ENU 轉換
|
|
|
|
|
msg.pose.pose.position.x = float(local_pos['x'])
|
|
|
|
|
msg.pose.pose.position.y = float(local_pos['y'])
|
|
|
|
|
msg.pose.pose.position.z = float(local_pos['z'])
|
|
|
|
|
|
|
|
|
|
msg.twist.twist.linear.x = float(local_pos['vx'])
|
|
|
|
|
msg.twist.twist.linear.y = float(local_pos['vy'])
|
|
|
|
|
msg.twist.twist.linear.z = float(local_pos['vz'])
|
|
|
|
|
|
|
|
|
|
publisher.publish(msg)
|
|
|
|
|
|
|
|
|
|
def _publish_attitude(self, sysid: int, status: mvv.ComponentStatus):
|
|
|
|
|
"""發布姿態(IMU)"""
|
|
|
|
|
@ -257,7 +296,6 @@ class VehicleStatusPublisher(Node):
|
|
|
|
|
|
|
|
|
|
publisher.publish(msg)
|
|
|
|
|
|
|
|
|
|
# TODO 這邊要改成 XY 的位置與速度
|
|
|
|
|
def _publish_velocity(self, sysid: int, status: mvv.ComponentStatus):
|
|
|
|
|
"""發布速度"""
|
|
|
|
|
if not self.rate_controller.should_publish(sysid, 'velocity'):
|
|
|
|
|
|