@ -1,10 +1,15 @@
"""
"""
MAVLink ROS2 Nodes
MAVLink ROS2 Nodes
包含兩個獨立的 ROS2 Node :
主要 包含兩個獨立的 ROS2 Node :
1. VehicleStatusPublisher - 發布載具狀態到 ROS2 topics
1. VehicleStatusPublisher - 發布載具狀態到 ROS2 topics
從 vehicle_registry 讀取狀態數據 , 頻率控制 , 模組化設計
2. MavlinkCommandService - 提供 MAVLink 指令 service 介面
2. MavlinkCommandService - 提供 MAVLink 指令 service 介面
以最基礎的 mavlink microservice 會實現目標
並不會包含額外的功能
與一個節點管理器
- fc_ros_manager
從 vehicle_registry 讀取狀態數據 , 頻率控制 , 模組化設計
"""
"""
import os
import os
@ -26,6 +31,7 @@ import mavros_msgs.msg
# ROS2 Service imports
# ROS2 Service imports
import fc_interfaces . srv as fcsrv
import fc_interfaces . srv as fcsrv
from . ackEnum import serviceAckResult
# 自定義 imports
# 自定義 imports
from . import mavlinkVehicleView as mvv
from . import mavlinkVehicleView as mvv
@ -521,6 +527,15 @@ class MavlinkCommandService(Node):
self . handle_command_long
self . handle_command_long
)
)
# ═══════════════════════════════════════════════════════════════════
# Service : 發送 SET_POSITION_TARGET_GLOBAL_INT (86)
# ═══════════════════════════════════════════════════════════════════
self . srv_pos_global_int = self . create_service (
fcsrv . MavPositionTargetGlobalInt ,
self . serviceString_prefix + ' /pos_global_int ' ,
self . handle_set_position_target_global_int
)
logger . info ( " MavlinkCommandService initialized " )
logger . info ( " MavlinkCommandService initialized " )
def _index ( self , target_sysid , target_compid ) :
def _index ( self , target_sysid , target_compid ) :
@ -568,6 +583,7 @@ class MavlinkCommandService(Node):
def handle_mav_timesync_ping ( self , request , response ) :
def handle_mav_timesync_ping ( self , request , response ) :
'''
'''
用 timesync 封包驗證來回的時間
用 timesync 封包驗證來回的時間
隸屬於 MavLink PING Protocol
'''
'''
# 設定失效回應
# 設定失效回應
response . success = False
response . success = False
@ -612,7 +628,7 @@ class MavlinkCommandService(Node):
fail_skip = False
fail_skip = False
# 5) 等待回應封包
# 5) 等待回應封包
if not evt . wait ( timeout_sec ) :
if not evt . wait ( timeout_sec ) :
response . message = " waiting T imeout - TIMESYNC"
response . message = " mavlink t imeout - TIMESYNC"
fail_skip = True
fail_skip = True
# 6) 處理回應封包
# 6) 處理回應封包
@ -633,35 +649,31 @@ class MavlinkCommandService(Node):
return response
return response
def handle_add_two_ints ( self , request , response ) :
""" 測試用 Service Handler 未來刪除 """
logger . info ( f " Received add_two_ints request: { request . a } + { request . b } " )
response . sum = request . a + request . b
logger . info (
f " [add_two_ints] thread_ident= { threading . get_ident ( ) } time= { time . time ( ) } "
)
time . sleep ( 1 )
return response
# ═══════════════════════════════════════════════════════════════════════
# ═══════════════════════════════════════════════════════════════════════
# Service Handler: 發送 COMMAND_LONG
# Service Handler: 發送 COMMAND_LONG (76)
# ═══════════════════════════════════════════════════════════════════════
# ═══════════════════════════════════════════════════════════════════════
def handle_command_long ( self , request , response ) :
def handle_command_long ( self , request , response ) :
'''
用 command long 丟出 MAV_CMD
隸屬於 MavLink Command Protocol
'''
# 設定失效回應
# 設定失效回應
response . success = False
response . success = False
response . message = " Unknown error "
response . message = " Unknown error "
response . ack_result = serviceAckResult . UNKNOWN
timeout_sec = request . timeout_sec
timeout_sec = request . timeout_sec
# 1) 確認是否已經有相同 sysid 的其他需求正在 pending
# 1) 確認是否已經有相同 sysid 的其他需求正在 pending
if request . target_sysid in self . _pending_by_sysid :
if request . target_sysid in self . _pending_by_sysid :
response . message = f " sysid { request . target_sysid } already has pending request "
response . message = f " sysid { request . target_sysid } already has pending request "
response . ack_result = serviceAckResult . MAVLINK_BUSY
return response
return response
# 2) 找到 socket 標地
# 2) 找到 socket 標地
socketObject = self . _index ( request . target_sysid , request . target_compid )
socketObject = self . _index ( request . target_sysid , request . target_compid )
if socketObject is None :
if socketObject is None :
response . message = " This system id not found. "
response . message = " This system id not found. "
response . ack_result = serviceAckResult . MAVLINK_DEV_NOTFOUND
return response
return response
# 3) 接收封包系統 的設定
# 3) 接收封包系統 的設定
@ -691,7 +703,8 @@ class MavlinkCommandService(Node):
fail_skip = False
fail_skip = False
# 5) 等待回應封包
# 5) 等待回應封包
if not evt . wait ( timeout_sec ) :
if not evt . wait ( timeout_sec ) :
response . message = " waiting Timeout - CommLONG "
response . message = " mavlink timeout - CommLONG "
response . ack_result = serviceAckResult . MAVLINK_TIMEOUT
fail_skip = True
fail_skip = True
# 6) 處理回應封包
# 6) 處理回應封包
@ -711,7 +724,96 @@ class MavlinkCommandService(Node):
return response
return response
# ═══════════════════════════════════════════════════════════════════════
# Service Handler: 發送 SET_POSITION_TARGET_GLOBAL_INT (86)
# ═══════════════════════════════════════════════════════════════════════
def handle_set_position_target_global_int ( self , request , response ) :
'''
隸屬於 MavLink Offboard Control Protocol
'''
# 設定失效回應
response . message = " Unknown error "
response . ack_result = serviceAckResult . UNKNOWN
timeout_sec = request . timeout_sec
# 1) 確認是否已經有相同 sysid 的其他需求正在 pending
if request . target_sysid in self . _pending_by_sysid :
response . message = f " sysid { request . target_sysid } already has pending request "
response . ack_result = serviceAckResult . MAVLINK_BUSY
return response
# 2) 找到 socket 標地
socketObject = self . _index ( request . target_sysid , request . target_compid )
if socketObject is None :
response . message = " This system id not found. "
response . ack_result = serviceAckResult . MAVLINK_DEV_NOTFOUND
return response
# 3) 接收封包系統 的設定
# 在 socket 那邊先把要的封包種類導流進來
expect_recieve_msg_id = 87 # POSITION_TARGET_GLOBAL_INT
socketObject . set_return_message_types ( list ( socketObject . return_msg_types ) + [ expect_recieve_msg_id ] )
evt = threading . Event ( )
# 設定封包檢驗
def match_fn ( compare_msg ) :
if compare_msg . get_msgId ( ) != expect_recieve_msg_id :
return False
return True
# 4) 送出封包
socketObject . MAVLink . set_position_target_global_int_send (
request . time_boot_ms ,
request . target_sysid ,
request . target_compid ,
request . coordinate_frame ,
request . type_mask ,
request . lat_int , request . lon_int , request . alt ,
request . vx , request . vy , request . vz ,
request . afx , request . afy , request . afz ,
request . yaw , request . yaw_rate
)
time . sleep ( 0.01 ) # 因應 mavlink 的廣播式回應 後置回應監聽 並且故意延遲10ms 讓系統代謝掉舊的87封包
_pending = PendingEntry ( event = evt , match_fn = match_fn )
self . _pending_by_sysid [ request . target_sysid ] = _pending
fail_skip = False
# 5) 等待回應封包
if not evt . wait ( timeout_sec ) :
response . message = " mavlink timeout - SET POSITION 86 "
response . ack_result = MAVLINK_SEND_BUT_NO_EXP_STEAM
fail_skip = True
# 6) 處理回應封包
if not fail_skip :
ack_msg = _pending . result_mav_msg
response . message = " "
response . ack_result = 0
response . r_time_boot_ms = ack_msg . time_boot_ms
response . r_type_mask = ack_msg . type_mask
response . r_lat_int = ack_msg . lat_int
response . r_lon_int = ack_msg . lon_int
response . r_alt = ack_msg . alt
response . r_vx = ack_msg . vx
response . r_vy = ack_msg . vy
response . r_vz = ack_msg . vz
response . r_afx = ack_msg . afx
response . r_afy = ack_msg . afy
response . r_afz = ack_msg . afz
response . r_yaw = ack_msg . yaw
response . r_yaw_rate = ack_msg . yaw_rate
# 7) 接收封包系統 的重置
msg_types = list ( socketObject . return_msg_types )
if expect_recieve_msg_id in msg_types :
msg_types . remove ( expect_recieve_msg_id )
socketObject . set_return_message_types ( msg_types )
del evt
self . _pending_by_sysid . pop ( request . target_sysid , None )
return response
# ═══════════════════════════════════════════════════════════════════════
# ═══════════════════════════════════════════════════════════════════════
# Service Handler: 參數請求
# Service Handler: 參數請求
# ═══════════════════════════════════════════════════════════════════════
# ═══════════════════════════════════════════════════════════════════════
@ -790,7 +892,21 @@ class MavlinkCommandService(Node):
response . success = True
response . success = True
response . message = " Param request sent (placeholder implementation) "
response . message = " Param request sent (placeholder implementation) "
return response
return response
def handle_add_two_ints ( self , request , response ) :
""" 測試用 Service Handler 未來刪除 """
logger . info ( f " Received add_two_ints request: { request . a } + { request . b } " )
response . sum = request . a + request . b
logger . info (
f " [add_two_ints] thread_ident= { threading . get_ident ( ) } time= { time . time ( ) } "
)
time . sleep ( 1 )
return response
def stop ( self ) :
def stop ( self ) :
""" 停止服務 """
""" 停止服務 """
self . running = False
self . running = False
@ -973,7 +1089,11 @@ ros2_manager = fc_ros_manager()
5. 預留 MavlinkCommandService 結構 ( 稍後實現 )
5. 預留 MavlinkCommandService 結構 ( 稍後實現 )
2026.03 .27
2026.03 .27
1. 完成 ros2 service 結構與 timesync command_long 協議
1. 完成 ros2 service 結構與 timesync 與 command_long 協議
2026.04 .07
1. 完成 ros2 的 MavPositionTargetGlobalInt 區域
2. 優化 response . ack_result 回傳值的資訊
'''
'''