@@ -675,6 +675,19 @@ def heartbeat_is_from_autopilot(self, m):
675
675
676
676
return True
677
677
678
+ mav_type_planes = [
679
+ mavutil .mavlink .MAV_TYPE_FIXED_WING ,
680
+ mavutil .mavlink .MAV_TYPE_VTOL_QUADROTOR ,
681
+ mavutil .mavlink .MAV_TYPE_VTOL_TILTROTOR ,
682
+ ]
683
+ # DUOROTOR was renamed to MAV_TYPE_
684
+ for possible_plane_type in "VTOL_DUOROTOR" , "VTOL_TAILSITTER_DUOROTOR" :
685
+ t = f"MAV_TYPE_{ possible_plane_type } "
686
+ attr = getattr (mavutil .mavlink , t , None )
687
+ if attr is None :
688
+ continue
689
+ mav_type_planes .append (attr )
690
+
678
691
def master_msg_handling (self , m , master ):
679
692
'''link message handling for an upstream link'''
680
693
@@ -739,11 +752,7 @@ def master_msg_handling(self, m, master):
739
752
self .status .last_mode_announced = master .flightmode
740
753
self .say ("Mode " + self .status .flightmode )
741
754
742
- if m .type in [
743
- mavutil .mavlink .MAV_TYPE_FIXED_WING ,
744
- mavutil .mavlink .MAV_TYPE_VTOL_DUOROTOR ,
745
- mavutil .mavlink .MAV_TYPE_VTOL_QUADROTOR ,
746
- mavutil .mavlink .MAV_TYPE_VTOL_TILTROTOR ]:
755
+ if m .type in self .mav_type_planes :
747
756
self .mpstate .vehicle_type = 'plane'
748
757
self .mpstate .vehicle_name = 'ArduPlane'
749
758
elif m .type in [mavutil .mavlink .MAV_TYPE_GROUND_ROVER ,
0 commit comments