diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index b31ae5c848..25058e3a10 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -912,9 +912,9 @@ AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const return AP_GPS::GPS_OK_FIX_3D; } +#if HAL_LOGGING_ENABLED bool AP_GPS::should_log() const { -#if HAL_LOGGING_ENABLED AP_Logger *logger = AP_Logger::get_singleton(); if (logger == nullptr) { return false; @@ -926,10 +926,8 @@ bool AP_GPS::should_log() const return false; } return true; -#else - return false; -#endif } +#endif /* @@ -1775,6 +1773,7 @@ bool AP_GPS::parse_rtcm_injection(mavlink_channel_t chan, const mavlink_gps_rtcm } #endif // AP_GPS_RTCM_DECODE_ENABLED +#if HAL_LOGGING_ENABLED void AP_GPS::Write_AP_Logger_Log_Startup_messages() { for (uint8_t instance=0; instanceWrite_AP_Logger_Log_Startup_messages(); } } +#endif /* return the expected lag (in seconds) in the position and velocity readings from the gps diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h index 3efa390427..514c2b59d8 100644 --- a/libraries/AP_GPS/AP_GPS.h +++ b/libraries/AP_GPS/AP_GPS.h @@ -530,7 +530,9 @@ public: static const struct AP_Param::GroupInfo var_info[]; +#if HAL_LOGGING_ENABLED void Write_AP_Logger_Log_Startup_messages(); +#endif // indicate which bit in LOG_BITMASK indicates gps logging enabled void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; } diff --git a/libraries/AP_GPS/AP_GPS_NMEA.cpp b/libraries/AP_GPS/AP_GPS_NMEA.cpp index 1712f6754b..0ec48ce9ae 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.cpp +++ b/libraries/AP_GPS/AP_GPS_NMEA.cpp @@ -957,9 +957,9 @@ bool AP_GPS_NMEA::get_lag(float &lag_sec) const return true; } +#if HAL_LOGGING_ENABLED void AP_GPS_NMEA::Write_AP_Logger_Log_Startup_messages() const { -#if HAL_LOGGING_ENABLED AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages(); #if AP_GPS_NMEA_UNICORE_ENABLED if (_have_unicore_versiona) { @@ -970,7 +970,7 @@ void AP_GPS_NMEA::Write_AP_Logger_Log_Startup_messages() const _versiona.build_date); } #endif -#endif } +#endif #endif // AP_GPS_NMEA_ENABLED diff --git a/libraries/AP_GPS/AP_GPS_NMEA.h b/libraries/AP_GPS/AP_GPS_NMEA.h index 330a7b5870..3109600b4e 100644 --- a/libraries/AP_GPS/AP_GPS_NMEA.h +++ b/libraries/AP_GPS/AP_GPS_NMEA.h @@ -72,7 +72,9 @@ public: // get lag in seconds bool get_lag(float &lag_sec) const override; +#if HAL_LOGGING_ENABLED void Write_AP_Logger_Log_Startup_messages() const override; +#endif private: /// Coding for the GPS sentences that the parser handles diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index f073201373..9d9604f21f 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -2111,9 +2111,9 @@ bool AP_GPS_UBLOX::get_lag(float &lag_sec) const return true; } +#if HAL_LOGGING_ENABLED void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const { -#if HAL_LOGGING_ENABLED AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages(); if (_have_version) { @@ -2122,8 +2122,8 @@ void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const _version.hwVersion, _version.swVersion); } -#endif } +#endif // uBlox specific check_new_itow(), handling message length void AP_GPS_UBLOX::_check_new_itow(uint32_t itow) diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.h b/libraries/AP_GPS/AP_GPS_UBLOX.h index cbf21f925d..738dac3b42 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.h +++ b/libraries/AP_GPS/AP_GPS_UBLOX.h @@ -152,7 +152,9 @@ public: }; void broadcast_configuration_failure_reason(void) const override; +#if HAL_LOGGING_ENABLED void Write_AP_Logger_Log_Startup_messages() const override; +#endif // get the velocity lag, returns true if the driver is confident in the returned value bool get_lag(float &lag_sec) const override; diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 7631837860..a976ea280c 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -156,19 +156,19 @@ void AP_GPS_Backend::broadcast_gps_type() const GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", buffer); } +#if HAL_LOGGING_ENABLED void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const { -#if HAL_LOGGING_ENABLED char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; _detection_message(buffer, sizeof(buffer)); AP::logger().Write_Message(buffer); -#endif } bool AP_GPS_Backend::should_log() const { return gps.should_log(); } +#endif #if HAL_GCS_ENABLED diff --git a/libraries/AP_GPS/GPS_Backend.h b/libraries/AP_GPS/GPS_Backend.h index 2fdae674d9..2544fcdefb 100644 --- a/libraries/AP_GPS/GPS_Backend.h +++ b/libraries/AP_GPS/GPS_Backend.h @@ -95,7 +95,9 @@ public: virtual const char *name() const = 0; void broadcast_gps_type() const; +#if HAL_LOGGING_ENABLED virtual void Write_AP_Logger_Log_Startup_messages() const; +#endif virtual bool prepare_for_arming(void) { return true; }