mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: exclude more code based on HAL_LOGGING_ENABLED
This commit is contained in:
parent
7794f7fdaa
commit
4811a10e1a
|
@ -912,9 +912,9 @@ AP_GPS::GPS_Status AP_GPS::highest_supported_status(uint8_t instance) const
|
||||||
return AP_GPS::GPS_OK_FIX_3D;
|
return AP_GPS::GPS_OK_FIX_3D;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
bool AP_GPS::should_log() const
|
bool AP_GPS::should_log() const
|
||||||
{
|
{
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
AP_Logger *logger = AP_Logger::get_singleton();
|
AP_Logger *logger = AP_Logger::get_singleton();
|
||||||
if (logger == nullptr) {
|
if (logger == nullptr) {
|
||||||
return false;
|
return false;
|
||||||
|
@ -926,10 +926,8 @@ bool AP_GPS::should_log() const
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
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
|
#endif // AP_GPS_RTCM_DECODE_ENABLED
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_GPS::Write_AP_Logger_Log_Startup_messages()
|
void AP_GPS::Write_AP_Logger_Log_Startup_messages()
|
||||||
{
|
{
|
||||||
for (uint8_t instance=0; instance<num_instances; instance++) {
|
for (uint8_t instance=0; instance<num_instances; instance++) {
|
||||||
|
@ -1784,6 +1783,7 @@ void AP_GPS::Write_AP_Logger_Log_Startup_messages()
|
||||||
drivers[instance]->Write_AP_Logger_Log_Startup_messages();
|
drivers[instance]->Write_AP_Logger_Log_Startup_messages();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
return the expected lag (in seconds) in the position and velocity readings from the gps
|
return the expected lag (in seconds) in the position and velocity readings from the gps
|
||||||
|
|
|
@ -530,7 +530,9 @@ public:
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void Write_AP_Logger_Log_Startup_messages();
|
void Write_AP_Logger_Log_Startup_messages();
|
||||||
|
#endif
|
||||||
|
|
||||||
// indicate which bit in LOG_BITMASK indicates gps logging enabled
|
// indicate which bit in LOG_BITMASK indicates gps logging enabled
|
||||||
void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; }
|
void set_log_gps_bit(uint32_t bit) { _log_gps_bit = bit; }
|
||||||
|
|
|
@ -957,9 +957,9 @@ bool AP_GPS_NMEA::get_lag(float &lag_sec) const
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_GPS_NMEA::Write_AP_Logger_Log_Startup_messages() const
|
void AP_GPS_NMEA::Write_AP_Logger_Log_Startup_messages() const
|
||||||
{
|
{
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
|
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
|
||||||
#if AP_GPS_NMEA_UNICORE_ENABLED
|
#if AP_GPS_NMEA_UNICORE_ENABLED
|
||||||
if (_have_unicore_versiona) {
|
if (_have_unicore_versiona) {
|
||||||
|
@ -970,7 +970,7 @@ void AP_GPS_NMEA::Write_AP_Logger_Log_Startup_messages() const
|
||||||
_versiona.build_date);
|
_versiona.build_date);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // AP_GPS_NMEA_ENABLED
|
#endif // AP_GPS_NMEA_ENABLED
|
||||||
|
|
|
@ -72,7 +72,9 @@ public:
|
||||||
// get lag in seconds
|
// get lag in seconds
|
||||||
bool get_lag(float &lag_sec) const override;
|
bool get_lag(float &lag_sec) const override;
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void Write_AP_Logger_Log_Startup_messages() const override;
|
void Write_AP_Logger_Log_Startup_messages() const override;
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/// Coding for the GPS sentences that the parser handles
|
/// Coding for the GPS sentences that the parser handles
|
||||||
|
|
|
@ -2111,9 +2111,9 @@ bool AP_GPS_UBLOX::get_lag(float &lag_sec) const
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const
|
void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const
|
||||||
{
|
{
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
|
AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages();
|
||||||
|
|
||||||
if (_have_version) {
|
if (_have_version) {
|
||||||
|
@ -2122,8 +2122,8 @@ void AP_GPS_UBLOX::Write_AP_Logger_Log_Startup_messages() const
|
||||||
_version.hwVersion,
|
_version.hwVersion,
|
||||||
_version.swVersion);
|
_version.swVersion);
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// uBlox specific check_new_itow(), handling message length
|
// uBlox specific check_new_itow(), handling message length
|
||||||
void AP_GPS_UBLOX::_check_new_itow(uint32_t itow)
|
void AP_GPS_UBLOX::_check_new_itow(uint32_t itow)
|
||||||
|
|
|
@ -152,7 +152,9 @@ public:
|
||||||
};
|
};
|
||||||
|
|
||||||
void broadcast_configuration_failure_reason(void) const override;
|
void broadcast_configuration_failure_reason(void) const override;
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void Write_AP_Logger_Log_Startup_messages() const override;
|
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
|
// get the velocity lag, returns true if the driver is confident in the returned value
|
||||||
bool get_lag(float &lag_sec) const override;
|
bool get_lag(float &lag_sec) const override;
|
||||||
|
|
|
@ -156,19 +156,19 @@ void AP_GPS_Backend::broadcast_gps_type() const
|
||||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", buffer);
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "%s", buffer);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const
|
void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const
|
||||||
{
|
{
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
char buffer[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
|
||||||
_detection_message(buffer, sizeof(buffer));
|
_detection_message(buffer, sizeof(buffer));
|
||||||
AP::logger().Write_Message(buffer);
|
AP::logger().Write_Message(buffer);
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool AP_GPS_Backend::should_log() const
|
bool AP_GPS_Backend::should_log() const
|
||||||
{
|
{
|
||||||
return gps.should_log();
|
return gps.should_log();
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if HAL_GCS_ENABLED
|
#if HAL_GCS_ENABLED
|
||||||
|
|
|
@ -95,7 +95,9 @@ public:
|
||||||
virtual const char *name() const = 0;
|
virtual const char *name() const = 0;
|
||||||
|
|
||||||
void broadcast_gps_type() const;
|
void broadcast_gps_type() const;
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
virtual void Write_AP_Logger_Log_Startup_messages() const;
|
virtual void Write_AP_Logger_Log_Startup_messages() const;
|
||||||
|
#endif
|
||||||
|
|
||||||
virtual bool prepare_for_arming(void) { return true; }
|
virtual bool prepare_for_arming(void) { return true; }
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue