diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 7462646240..51506383ba 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -698,7 +698,7 @@ AP_GPS_UBLOX::read(void) // Private Methods ///////////////////////////////////////////////////////////// void AP_GPS_UBLOX::log_mon_hw(void) { -#ifndef HAL_NO_LOGGING +#if HAL_LOGGING_ENABLED if (!should_log()) { return; } @@ -724,7 +724,7 @@ void AP_GPS_UBLOX::log_mon_hw(void) void AP_GPS_UBLOX::log_mon_hw2(void) { -#ifndef HAL_NO_LOGGING +#if HAL_LOGGING_ENABLED if (!should_log()) { return; } @@ -745,7 +745,7 @@ void AP_GPS_UBLOX::log_mon_hw2(void) #if UBLOX_RXM_RAW_LOGGING void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw) { -#ifndef HAL_NO_LOGGING +#if HAL_LOGGING_ENABLED if (!should_log()) { return; } @@ -773,7 +773,7 @@ void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw) void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw) { -#ifndef HAL_NO_LOGGING +#if HAL_LOGGING_ENABLED if (!should_log()) { return; } @@ -1876,7 +1876,7 @@ bool AP_GPS_UBLOX::get_lag(float &lag_sec) const void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const { -#ifndef HAL_NO_LOGGING +#if HAL_LOGGING_ENABLED AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages(); if (_have_version) { diff --git a/libraries/AP_GPS/GPS_Backend.cpp b/libraries/AP_GPS/GPS_Backend.cpp index 2877e18f4a..65d00a9c46 100644 --- a/libraries/AP_GPS/GPS_Backend.cpp +++ b/libraries/AP_GPS/GPS_Backend.cpp @@ -160,7 +160,7 @@ void AP_GPS_Backend::broadcast_gps_type() const void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const { -#ifndef HAL_NO_LOGGING +#if HAL_LOGGING_ENABLED char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1]; _detection_message(buffer, sizeof(buffer)); AP::logger().Write_Message(buffer);