@@ -85,6 +85,7 @@ def __init__(self, mpstate):
8585 self .vehicle_name_by_sysid = {}
8686 self .component_name = {}
8787 self .last_param_sysid_timestamp = None
88+ self .flight_information = {}
8889
8990 # create the main menu
9091 if mp_util .has_wxpython :
@@ -415,6 +416,13 @@ def handle_vfr_hud(self, msg):
415416 self .console .set_status ('AirSpeed' , 'AirSpeed %s' % self .speed_string (msg .airspeed ))
416417 self .console .set_status ('GPSSpeed' , 'GPSSpeed %s' % self .speed_string (msg .groundspeed ))
417418 self .console .set_status ('Thr' , 'Thr %u' % msg .throttle )
419+
420+ sysid = msg .get_srcSystem ()
421+ if (sysid not in self .flight_information or
422+ self .flight_information [sysid ].supported != True ):
423+ self .update_flight_time_from_vfr_hud (msg )
424+
425+ def update_flight_time_from_vfr_hud (self , msg ):
418426 t = time .localtime (msg ._timestamp )
419427 flying = False
420428 if self .mpstate .vehicle_type == 'copter' :
@@ -713,6 +721,36 @@ def handle_high_latency2(self, msg):
713721 else :
714722 self .console .set_status ('PWR' , 'PWR OK' , fg = 'green' )
715723
724+ def handle_flight_information (self , msg ):
725+ sysid = msg .get_srcSystem ()
726+ if sysid not in self .flight_information :
727+ self .flight_information [sysid ] = ConsoleModule .FlightInformation (sysid )
728+ self .flight_information [sysid ].last_seen = time .time ()
729+
730+ # NOTE! the takeoff_time_utc field is misnamed in the XML!
731+ if msg .takeoff_time_utc == 0 :
732+ # 0 is "landed", so don't update so we preserve the last
733+ # flight tiem in the display
734+ return
735+ total_time = (msg .time_boot_ms - msg .takeoff_time_utc * 0.001 ) * 0.001
736+ self .console .set_status ('FlightTime' , 'FlightTime %u:%02u' % (int (total_time )/ 60 , int (total_time )% 60 ))
737+
738+ def handle_command_ack (self , msg ):
739+ sysid = msg .get_srcSystem ()
740+
741+ if msg .command != mavutil .mavlink .MAV_CMD_SET_MESSAGE_INTERVAL :
742+ return
743+
744+ if sysid not in self .flight_information :
745+ return
746+
747+ fi = self .flight_information [sysid ]
748+
749+ if msg .result == mavutil .mavlink .MAV_RESULT_ACCEPTED :
750+ fi .supported = True
751+ elif msg .result in [mavutil .mavlink .MAV_RESULT_DENIED , mavutil .mavlink .MAV_RESULT_FAILED ]:
752+ fi .supported = False
753+
716754 # update user-added console entries; called after a mavlink packet
717755 # is received:
718756 def update_user_added_keys (self , msg ):
@@ -808,11 +846,66 @@ def mavlink_packet(self, msg):
808846 elif type == 'PARAM_VALUE' :
809847 self .handle_param_value (msg )
810848
849+ # note that we also process this as a HEARTBEAT message above!
811850 if type == 'HIGH_LATENCY2' :
812851 self .handle_high_latency2 (msg )
813852
853+ elif type == 'FLIGHT_INFORMATION' :
854+ self .handle_flight_information (msg )
855+
856+ elif type == 'COMMAND_ACK' :
857+ self .handle_command_ack (msg )
858+
814859 self .update_user_added_keys (msg )
815860
861+ # we've received a packet from the vehicle; probe for
862+ # FLIGHT_INFORMATION support:
863+ self .probe_for_flight_information (msg .get_srcSystem (), msg .get_srcComponent ())
864+
865+ class FlightInformation ():
866+ def __init__ (self , sysid ):
867+ self .sysid = sysid
868+ self .supported = None # don't know
869+ self .last_seen = None # last time we saw FLIGHT_INFORMATION
870+ self .last_set_message_interval_sent = None # last time we sent set-interval
871+
872+ def probe_for_flight_information (self , sysid , compid ):
873+ '''if we don't know if this vehicle supports flight information,
874+ request it'''
875+ if sysid not in self .flight_information :
876+ self .flight_information [sysid ] = ConsoleModule .FlightInformation (sysid )
877+
878+ fi = self .flight_information [sysid ]
879+
880+ now = time .time ()
881+
882+ if fi .supported is not False and (fi .last_seen is None or now - fi .last_seen > 10 ):
883+ # if we stop getting FLIGHT_INFORMATION, re-request it:
884+ fi .supported = None
885+
886+ if fi .supported is True or fi .supported is False :
887+ # we know one way or the other
888+ return
889+
890+ # only probe once every 10 seconds
891+ if (fi .last_set_message_interval_sent is not None and
892+ now - fi .last_set_message_interval_sent < 10 ):
893+ return
894+ fi .last_set_message_interval_sent = now
895+
896+ self .master .mav .command_long_send (
897+ sysid ,
898+ compid ,
899+ mavutil .mavlink .MAV_CMD_SET_MESSAGE_INTERVAL ,
900+ 0 , # confirmation
901+ mavutil .mavlink .MAVLINK_MSG_ID_FLIGHT_INFORMATION , # msg id
902+ 500000 , # interval - 2Hz
903+ 0 , # p3
904+ 0 , # p4
905+ 0 , # p5
906+ 0 , # p6
907+ 0 ) # p7
908+
816909 def idle_task (self ):
817910 now = time .time ()
818911 if self .last_unload_check_time + self .unload_check_interval < now :
0 commit comments