|
|
|
@ -40,11 +40,11 @@ from .utils import setup_logger
|
|
|
|
|
|
|
|
|
|
|
|
logger = setup_logger(os.path.basename(__file__))
|
|
|
|
logger = setup_logger(os.path.basename(__file__))
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# ============================================================================
|
|
|
|
# ============================================================================
|
|
|
|
# 頻率控制器
|
|
|
|
# VehicleStatusPublisher Node
|
|
|
|
# ============================================================================
|
|
|
|
# ============================================================================
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# 頻率控制器
|
|
|
|
class PublishRateController:
|
|
|
|
class PublishRateController:
|
|
|
|
"""發布頻率控制器 - 按時間間隔控制發布頻率"""
|
|
|
|
"""發布頻率控制器 - 按時間間隔控制發布頻率"""
|
|
|
|
|
|
|
|
|
|
|
|
@ -103,11 +103,6 @@ class PublishRateController:
|
|
|
|
"""重置所有計時器"""
|
|
|
|
"""重置所有計時器"""
|
|
|
|
self.last_publish_time.clear()
|
|
|
|
self.last_publish_time.clear()
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
# ============================================================================
|
|
|
|
|
|
|
|
# VehicleStatusPublisher Node
|
|
|
|
|
|
|
|
# ============================================================================
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
class VehicleStatusPublisher(Node):
|
|
|
|
class VehicleStatusPublisher(Node):
|
|
|
|
"""
|
|
|
|
"""
|
|
|
|
載具狀態發布者 - 從 vehicle_registry 讀取數據並發布到 ROS2 topics
|
|
|
|
載具狀態發布者 - 從 vehicle_registry 讀取數據並發布到 ROS2 topics
|
|
|
|
@ -477,12 +472,17 @@ class MavlinkCommandService(Node):
|
|
|
|
- 作為 service server 等待 client 請求
|
|
|
|
- 作為 service server 等待 client 請求
|
|
|
|
- 接收請求,組裝 MAVLink 封包
|
|
|
|
- 接收請求,組裝 MAVLink 封包
|
|
|
|
- 調用 mavlinkObject 發送封包
|
|
|
|
- 調用 mavlinkObject 發送封包
|
|
|
|
- 處理 ACK 等待和超時(未來實現)
|
|
|
|
- 處理 ACK 等待和超時
|
|
|
|
|
|
|
|
|
|
|
|
設計理念:回歸 MAVLink 純粹結構
|
|
|
|
設計理念:回歸 MAVLink 純粹結構
|
|
|
|
- 只負責將 ROS2 請求轉換為 MAVLink 封包
|
|
|
|
- 只負責將 ROS2 請求轉換為 MAVLink 封包
|
|
|
|
- 不預設功能(如 ARM/DISARM) 保持模組化
|
|
|
|
- 不預設功能(如 ARM/DISARM) 保持模組化
|
|
|
|
- 高層應用可透過此 service 實現各種功能
|
|
|
|
- 高層應用可透過此 service 實現各種功能
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
講白話一點就是
|
|
|
|
|
|
|
|
每次接到一個 service 請求 要整個系統丟某種指令給載具時
|
|
|
|
|
|
|
|
會做兩件事 1."丟出mavlink封包" 2."創造一個臨時信箱 Pending"
|
|
|
|
|
|
|
|
|
|
|
|
"""
|
|
|
|
"""
|
|
|
|
|
|
|
|
|
|
|
|
serviceString_prefix = '/fc_network/vehicle'
|
|
|
|
serviceString_prefix = '/fc_network/vehicle'
|
|
|
|
@ -493,8 +493,8 @@ class MavlinkCommandService(Node):
|
|
|
|
# 狀態標記
|
|
|
|
# 狀態標記
|
|
|
|
self.running = True
|
|
|
|
self.running = True
|
|
|
|
|
|
|
|
|
|
|
|
# mavlinkObject 的引用(將由外部設置)
|
|
|
|
# # mavlinkObject 的引用(將由外部設置) 用不到
|
|
|
|
self.mavlink_analyzer = None
|
|
|
|
# self.mavlink_analyzer = None
|
|
|
|
|
|
|
|
|
|
|
|
# pending 旗標物件的儲存庫
|
|
|
|
# pending 旗標物件的儲存庫
|
|
|
|
self._pending_by_sysid = {} # sysid(int) : PendingEntry
|
|
|
|
self._pending_by_sysid = {} # sysid(int) : PendingEntry
|
|
|
|
@ -557,7 +557,8 @@ class MavlinkCommandService(Node):
|
|
|
|
|
|
|
|
|
|
|
|
def return_router(self):
|
|
|
|
def return_router(self):
|
|
|
|
'''
|
|
|
|
'''
|
|
|
|
這邊是給外部迴圈呼叫的 消耗 return_packet_ring 裡接收到的 mavlink 封包
|
|
|
|
在節點管理器哪邊被呼叫
|
|
|
|
|
|
|
|
消耗 return_packet_ring 裡接收到的 mavlink 封包
|
|
|
|
分送到各自的 pending 中
|
|
|
|
分送到各自的 pending 中
|
|
|
|
藉由 event.set() 解開 service 中的 block
|
|
|
|
藉由 event.set() 解開 service 中的 block
|
|
|
|
'''
|
|
|
|
'''
|
|
|
|
@ -953,7 +954,8 @@ class fc_ros_manager:
|
|
|
|
|
|
|
|
|
|
|
|
try:
|
|
|
|
try:
|
|
|
|
# 初始化 ROS2
|
|
|
|
# 初始化 ROS2
|
|
|
|
rclpy.init()
|
|
|
|
if not rclpy.ok():
|
|
|
|
|
|
|
|
rclpy.init(args=None)
|
|
|
|
|
|
|
|
|
|
|
|
# 創建節點 node
|
|
|
|
# 創建節點 node
|
|
|
|
self.status_publisher = VehicleStatusPublisher()
|
|
|
|
self.status_publisher = VehicleStatusPublisher()
|
|
|
|
@ -1095,5 +1097,9 @@ ros2_manager = fc_ros_manager()
|
|
|
|
1. 完成 ros2 的 MavPositionTargetGlobalInt 區域
|
|
|
|
1. 完成 ros2 的 MavPositionTargetGlobalInt 區域
|
|
|
|
2. 優化 response.ack_result 回傳值的資訊
|
|
|
|
2. 優化 response.ack_result 回傳值的資訊
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
TODO
|
|
|
|
|
|
|
|
1. service 部分會需要跟 mavlinkobject 大量互動 也許需要考慮對方的生命週期
|
|
|
|
|
|
|
|
2. 還沒測試 如果有失效狀態讓 fc_ros_manager 中斷了 如何恢復的問題
|
|
|
|
'''
|
|
|
|
'''
|
|
|
|
|
|
|
|
|
|
|
|
|