@@ -87,6 +87,7 @@ def __init__(self, mpstate):
8787 self .vehicle_name_by_sysid = {}
8888 self .component_name = {}
8989 self .last_param_sysid_timestamp = None
90+ self .flight_information = {}
9091
9192 # create the main menu
9293 if mp_util .has_wxpython :
@@ -429,6 +430,13 @@ def handle_vfr_hud(self, msg):
429430 self .console .set_status ('AirSpeed' , 'AirSpeed %s' % self .speed_string (msg .airspeed ))
430431 self .console .set_status ('GPSSpeed' , 'GPSSpeed %s' % self .speed_string (msg .groundspeed ))
431432 self .console .set_status ('Thr' , 'Thr %u' % msg .throttle )
433+
434+ sysid = msg .get_srcSystem ()
435+ if (sysid not in self .flight_information or
436+ self .flight_information [sysid ].supported != True ):
437+ self .update_flight_time_from_vfr_hud (msg )
438+
439+ def update_flight_time_from_vfr_hud (self , msg ):
432440 t = time .localtime (msg ._timestamp )
433441 flying = False
434442 if self .mpstate .vehicle_type == 'copter' :
@@ -730,6 +738,36 @@ def handle_high_latency2(self, msg):
730738 else :
731739 self .console .set_status ('PWR' , 'PWR OK' , fg = green )
732740
741+ def handle_flight_information (self , msg ):
742+ sysid = msg .get_srcSystem ()
743+ if sysid not in self .flight_information :
744+ self .flight_information [sysid ] = ConsoleModule .FlightInformation (sysid )
745+ self .flight_information [sysid ].last_seen = time .time ()
746+
747+ # NOTE! the takeoff_time_utc field is misnamed in the XML!
748+ if msg .takeoff_time_utc == 0 :
749+ # 0 is "landed", so don't update so we preserve the last
750+ # flight tiem in the display
751+ return
752+ total_time = (msg .time_boot_ms - msg .takeoff_time_utc * 0.001 ) * 0.001
753+ self .console .set_status ('FlightTime' , 'FlightTime %u:%02u' % (int (total_time )/ 60 , int (total_time )% 60 ))
754+
755+ def handle_command_ack (self , msg ):
756+ sysid = msg .get_srcSystem ()
757+
758+ if msg .command != mavutil .mavlink .MAV_CMD_SET_MESSAGE_INTERVAL :
759+ return
760+
761+ if sysid not in self .flight_information :
762+ return
763+
764+ fi = self .flight_information [sysid ]
765+
766+ if msg .result == mavutil .mavlink .MAV_RESULT_ACCEPTED :
767+ fi .supported = True
768+ elif msg .result in [mavutil .mavlink .MAV_RESULT_DENIED , mavutil .mavlink .MAV_RESULT_FAILED ]:
769+ fi .supported = False
770+
733771 # update user-added console entries; called after a mavlink packet
734772 # is received:
735773 def update_user_added_keys (self , msg ):
@@ -825,11 +863,66 @@ def mavlink_packet(self, msg):
825863 elif type == 'PARAM_VALUE' :
826864 self .handle_param_value (msg )
827865
866+ # note that we also process this as a HEARTBEAT message above!
828867 if type == 'HIGH_LATENCY2' :
829868 self .handle_high_latency2 (msg )
830869
870+ elif type == 'FLIGHT_INFORMATION' :
871+ self .handle_flight_information (msg )
872+
873+ elif type == 'COMMAND_ACK' :
874+ self .handle_command_ack (msg )
875+
831876 self .update_user_added_keys (msg )
832877
878+ # we've received a packet from the vehicle; probe for
879+ # FLIGHT_INFORMATION support:
880+ self .probe_for_flight_information (msg .get_srcSystem (), msg .get_srcComponent ())
881+
882+ class FlightInformation ():
883+ def __init__ (self , sysid ):
884+ self .sysid = sysid
885+ self .supported = None # don't know
886+ self .last_seen = None # last time we saw FLIGHT_INFORMATION
887+ self .last_set_message_interval_sent = None # last time we sent set-interval
888+
889+ def probe_for_flight_information (self , sysid , compid ):
890+ '''if we don't know if this vehicle supports flight information,
891+ request it'''
892+ if sysid not in self .flight_information :
893+ self .flight_information [sysid ] = ConsoleModule .FlightInformation (sysid )
894+
895+ fi = self .flight_information [sysid ]
896+
897+ now = time .time ()
898+
899+ if fi .supported is not False and (fi .last_seen is None or now - fi .last_seen > 10 ):
900+ # if we stop getting FLIGHT_INFORMATION, re-request it:
901+ fi .supported = None
902+
903+ if fi .supported is True or fi .supported is False :
904+ # we know one way or the other
905+ return
906+
907+ # only probe once every 10 seconds
908+ if (fi .last_set_message_interval_sent is not None and
909+ now - fi .last_set_message_interval_sent < 10 ):
910+ return
911+ fi .last_set_message_interval_sent = now
912+
913+ self .master .mav .command_long_send (
914+ sysid ,
915+ compid ,
916+ mavutil .mavlink .MAV_CMD_SET_MESSAGE_INTERVAL ,
917+ 0 , # confirmation
918+ mavutil .mavlink .MAVLINK_MSG_ID_FLIGHT_INFORMATION , # msg id
919+ 500000 , # interval - 2Hz
920+ 0 , # p3
921+ 0 , # p4
922+ 0 , # p5
923+ 0 , # p6
924+ 0 ) # p7
925+
833926 def idle_task (self ):
834927 now = time .time ()
835928 if self .last_unload_check_time + self .unload_check_interval < now :
0 commit comments