@@ -172,7 +172,9 @@ static uint8_t mavRates[] = {
172172 [MAV_DATA_STREAM_POSITION ] = 2 , // 2Hz
173173 [MAV_DATA_STREAM_EXTRA1 ] = 3 , // 3Hz
174174 [MAV_DATA_STREAM_EXTRA2 ] = 2 , // 2Hz, HEARTBEATs are important
175- [MAV_DATA_STREAM_EXTRA3 ] = 1 // 1Hz
175+ [MAV_DATA_STREAM_EXTRA3 ] = 1 , // 1Hz
176+ [MAV_DATA_STREAM_SYSTEM_TIME ] = 1 , // 1Hz
177+ [MAV_DATA_STREAM_HEARTBEAT ] = 1 , // 1Hz
176178};
177179
178180#define MAXSTREAMS (sizeof(mavRates) / sizeof(mavRates[0]))
@@ -704,52 +706,22 @@ void mavlinkSendAttitude(void)
704706 mavlinkSendMessage ();
705707}
706708
707- void mavlinkSendHUDAndHeartbeat (void )
709+ void mavlinkSendSystemTime (void )
708710{
709- float mavAltitude = 0 ;
710- float mavGroundSpeed = 0 ;
711- float mavAirSpeed = 0 ;
712- float mavClimbRate = 0 ;
711+ uint64_t timeUnixUsec = 0 ;
712+ rtcTime_t rtcTime ;
713713
714- #if defined(USE_GPS )
715- // use ground speed if source available
716- if (sensors (SENSOR_GPS )
717- #ifdef USE_GPS_FIX_ESTIMATION
718- || STATE (GPS_ESTIMATED_FIX )
719- #endif
720- ) {
721- mavGroundSpeed = gpsSol .groundSpeed / 100.0f ;
714+ if (rtcGet (& rtcTime )) {
715+ timeUnixUsec = (uint64_t )rtcTime * 1000ULL + (uint64_t )(micros () % 1000 ); // extrapolation to uS
716+ //timeUnixUsec = (uint64_t)rtcTime * 1000ULL; // mS resolution
722717 }
723- #endif
724-
725- #if defined(USE_PITOT )
726- if (sensors (SENSOR_PITOT ) && pitotIsHealthy ()) {
727- mavAirSpeed = getAirspeedEstimate () / 100.0f ;
728- }
729- #endif
730-
731- // select best source for altitude
732- mavAltitude = getEstimatedActualPosition (Z ) / 100.0f ;
733- mavClimbRate = getEstimatedActualVelocity (Z ) / 100.0f ;
734-
735- int16_t thr = getThrottlePercent (osdUsingScaledThrottle ());
736- mavlink_msg_vfr_hud_pack (mavSystemId , mavComponentId , & mavSendMsg ,
737- // airspeed Current airspeed in m/s
738- mavAirSpeed ,
739- // groundspeed Current ground speed in m/s
740- mavGroundSpeed ,
741- // heading Current heading in degrees, in compass units (0..360, 0=north)
742- DECIDEGREES_TO_DEGREES (attitude .values .yaw ),
743- // throttle Current throttle setting in integer percent, 0 to 100
744- thr ,
745- // alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
746- mavAltitude ,
747- // climb Current climb rate in meters/second
748- mavClimbRate );
749718
719+ mavlink_msg_system_time_pack (mavSystemId , mavComponentId , & mavSendMsg , timeUnixUsec , millis ());
750720 mavlinkSendMessage ();
721+ }
751722
752-
723+ void mavlinkSendHeartbeat (void )
724+ {
753725 uint8_t mavModes = MAV_MODE_FLAG_MANUAL_INPUT_ENABLED | MAV_MODE_FLAG_CUSTOM_MODE_ENABLED ;
754726 if (ARMING_FLAG (ARMED ))
755727 mavModes |= MAV_MODE_FLAG_SAFETY_ARMED ;
@@ -821,16 +793,62 @@ void mavlinkSendHUDAndHeartbeat(void)
821793 }
822794
823795 mavlink_msg_heartbeat_pack (mavSystemId , mavComponentId , & mavSendMsg ,
824- // type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
825- mavSystemType ,
826- // autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
827- mavType ,
828- // base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
829- mavModes ,
830- // custom_mode A bitfield for use for autopilot-specific flags.
831- mavCustomMode ,
832- // system_status System status flag, see MAV_STATE ENUM
833- mavSystemState );
796+ // type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
797+ mavSystemType ,
798+ // autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
799+ mavType ,
800+ // base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
801+ mavModes ,
802+ // custom_mode A bitfield for use for autopilot-specific flags.
803+ mavCustomMode ,
804+ // system_status System status flag, see MAV_STATE ENUM
805+ mavSystemState );
806+
807+ mavlinkSendMessage ();
808+ }
809+
810+ void mavlinkSendHUD (void )
811+ {
812+ float mavAltitude = 0 ;
813+ float mavGroundSpeed = 0 ;
814+ float mavAirSpeed = 0 ;
815+ float mavClimbRate = 0 ;
816+
817+ #if defined(USE_GPS )
818+ // use ground speed if source available
819+ if (sensors (SENSOR_GPS )
820+ #ifdef USE_GPS_FIX_ESTIMATION
821+ || STATE (GPS_ESTIMATED_FIX )
822+ #endif
823+ ) {
824+ mavGroundSpeed = gpsSol .groundSpeed / 100.0f ;
825+ }
826+ #endif
827+
828+ #if defined(USE_PITOT )
829+ if (sensors (SENSOR_PITOT ) && pitotIsHealthy ()) {
830+ mavAirSpeed = getAirspeedEstimate () / 100.0f ;
831+ }
832+ #endif
833+
834+ // select best source for altitude
835+ mavAltitude = getEstimatedActualPosition (Z ) / 100.0f ;
836+ mavClimbRate = getEstimatedActualVelocity (Z ) / 100.0f ;
837+
838+ int16_t thr = getThrottlePercent (osdUsingScaledThrottle ());
839+ mavlink_msg_vfr_hud_pack (mavSystemId , mavComponentId , & mavSendMsg ,
840+ // airspeed Current airspeed in m/s
841+ mavAirSpeed ,
842+ // groundspeed Current ground speed in m/s
843+ mavGroundSpeed ,
844+ // heading Current heading in degrees, in compass units (0..360, 0=north)
845+ DECIDEGREES_TO_DEGREES (attitude .values .yaw ),
846+ // throttle Current throttle setting in integer percent, 0 to 100
847+ thr ,
848+ // alt Current altitude (MSL), in meters, if we have surface or baro use them, otherwise use GPS (less accurate)
849+ mavAltitude ,
850+ // climb Current climb rate in meters/second
851+ mavClimbRate );
834852
835853 mavlinkSendMessage ();
836854}
@@ -952,13 +970,21 @@ void processMAVLinkTelemetry(timeUs_t currentTimeUs)
952970 }
953971
954972 if (mavlinkStreamTrigger (MAV_DATA_STREAM_EXTRA2 )) {
955- mavlinkSendHUDAndHeartbeat ();
973+ mavlinkSendHUD ();
956974 }
957975
958976 if (mavlinkStreamTrigger (MAV_DATA_STREAM_EXTRA3 )) {
959977 mavlinkSendBatteryTemperatureStatusText ();
960978 }
961979
980+ if (mavlinkStreamTrigger (MAV_DATA_STREAM_HEARTBEAT )) {
981+ mavlinkSendHeartbeat ();
982+ }
983+
984+ if (mavlinkStreamTrigger (MAV_DATA_STREAM_SYSTEM_TIME )) {
985+ mavlinkSendSystemTime ();
986+ }
987+
962988}
963989
964990static bool handleIncoming_MISSION_CLEAR_ALL (void )
0 commit comments