Browse Source

AP_GPS: rename dataflash to logger

master
Tom Pittenger 6 years ago committed by Peter Barker
parent
commit
12c3446777
  1. 12
      libraries/AP_GPS/AP_GPS.cpp
  2. 2
      libraries/AP_GPS/AP_GPS.h
  3. 2
      libraries/AP_GPS/AP_GPS_SBF.cpp
  4. 4
      libraries/AP_GPS/AP_GPS_SBP.cpp
  5. 8
      libraries/AP_GPS/AP_GPS_SBP2.cpp
  6. 8
      libraries/AP_GPS/AP_GPS_UBLOX.cpp
  7. 4
      libraries/AP_GPS/GPS_Backend.cpp
  8. 2
      libraries/AP_GPS/GPS_Backend.h

12
libraries/AP_GPS/AP_GPS.cpp

@ -133,7 +133,7 @@ const AP_Param::GroupInfo AP_GPS::var_info[] = {
// @Param: RAW_DATA // @Param: RAW_DATA
// @DisplayName: Raw data logging // @DisplayName: Raw data logging
// @Description: Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into dataflash log; on Septentrio this will log on the equipment's SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming // @Description: Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into logger; on Septentrio this will log on the equipment's SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming
// @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only) // @Values: 0:Ignore,1:Always log,2:Stop logging when disarmed (SBF only),5:Only log every five samples (uBlox only)
// @RebootRequired: True // @RebootRequired: True
// @User: Advanced // @User: Advanced
@ -559,16 +559,16 @@ 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;
} }
bool AP_GPS::should_df_log() const bool AP_GPS::should_log() const
{ {
AP_Logger *instance = AP_Logger::get_singleton(); AP_Logger *logger = AP_Logger::get_singleton();
if (instance == nullptr) { if (logger == nullptr) {
return false; return false;
} }
if (_log_gps_bit == (uint32_t)-1) { if (_log_gps_bit == (uint32_t)-1) {
return false; return false;
} }
if (!instance->should_log(_log_gps_bit)) { if (!logger->should_log(_log_gps_bit)) {
return false; return false;
} }
return true; return true;
@ -655,7 +655,7 @@ void AP_GPS::update_instance(uint8_t instance)
} }
if (data_should_be_logged && if (data_should_be_logged &&
should_df_log() && should_log() &&
!AP::ahrs().have_ekf_logging()) { !AP::ahrs().have_ekf_logging()) {
AP::logger().Write_GPS(instance); AP::logger().Write_GPS(instance);
} }

2
libraries/AP_GPS/AP_GPS.h

@ -558,7 +558,7 @@ private:
// calculate the blended state // calculate the blended state
void calc_blended_state(void); void calc_blended_state(void);
bool should_df_log() const; bool should_log() const;
// Auto configure types // Auto configure types
enum GPS_AUTO_CONFIG { enum GPS_AUTO_CONFIG {

2
libraries/AP_GPS/AP_GPS_SBF.cpp

@ -237,7 +237,7 @@ AP_GPS_SBF::parse(uint8_t temp)
void void
AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp) AP_GPS_SBF::log_ExtEventPVTGeodetic(const msg4007 &temp)
{ {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }

4
libraries/AP_GPS/AP_GPS_SBP.cpp

@ -392,7 +392,7 @@ void
AP_GPS_SBP::logging_log_full_update() AP_GPS_SBP::logging_log_full_update()
{ {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }
@ -412,7 +412,7 @@ AP_GPS_SBP::logging_log_raw_sbp(uint16_t msg_type,
uint16_t sender_id, uint16_t sender_id,
uint8_t msg_len, uint8_t msg_len,
uint8_t *msg_buff) { uint8_t *msg_buff) {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }

8
libraries/AP_GPS/AP_GPS_SBP2.cpp

@ -213,7 +213,7 @@ AP_GPS_SBP2::_sbp_process_message() {
} }
// send all messages we receive to log, even if it's an unsupported message, // send all messages we receive to log, even if it's an unsupported message,
// so we can do additional post-processing from Dataflash logs. // so we can do additional post-processing from logs.
// The log mask will be used to adjust or suppress logging // The log mask will be used to adjust or suppress logging
logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff); logging_log_raw_sbp(parser_state.msg_type, parser_state.sender_id, parser_state.msg_len, parser_state.msg_buff);
} }
@ -440,7 +440,7 @@ AP_GPS_SBP2::_detect(struct SBP2_detect_state &state, uint8_t data)
void void
AP_GPS_SBP2::logging_log_full_update() AP_GPS_SBP2::logging_log_full_update()
{ {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }
@ -462,7 +462,7 @@ AP_GPS_SBP2::logging_log_raw_sbp(uint16_t msg_type,
uint16_t sender_id, uint16_t sender_id,
uint8_t msg_len, uint8_t msg_len,
uint8_t *msg_buff) { uint8_t *msg_buff) {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }
@ -507,7 +507,7 @@ AP_GPS_SBP2::logging_log_raw_sbp(uint16_t msg_type,
void void
AP_GPS_SBP2::logging_ext_event() { AP_GPS_SBP2::logging_ext_event() {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }

8
libraries/AP_GPS/AP_GPS_UBLOX.cpp

@ -480,7 +480,7 @@ AP_GPS_UBLOX::read(void)
// Private Methods ///////////////////////////////////////////////////////////// // Private Methods /////////////////////////////////////////////////////////////
void AP_GPS_UBLOX::log_mon_hw(void) void AP_GPS_UBLOX::log_mon_hw(void)
{ {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }
struct log_Ubx1 pkt = { struct log_Ubx1 pkt = {
@ -504,7 +504,7 @@ void AP_GPS_UBLOX::log_mon_hw(void)
void AP_GPS_UBLOX::log_mon_hw2(void) void AP_GPS_UBLOX::log_mon_hw2(void)
{ {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }
@ -523,7 +523,7 @@ void AP_GPS_UBLOX::log_mon_hw2(void)
#if UBLOX_RXM_RAW_LOGGING #if UBLOX_RXM_RAW_LOGGING
void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw) void AP_GPS_UBLOX::log_rxm_raw(const struct ubx_rxm_raw &raw)
{ {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }
@ -549,7 +549,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) void AP_GPS_UBLOX::log_rxm_rawx(const struct ubx_rxm_rawx &raw)
{ {
if (!should_df_log()) { if (!should_log()) {
return; return;
} }

4
libraries/AP_GPS/GPS_Backend.cpp

@ -170,9 +170,9 @@ void AP_GPS_Backend::Write_AP_Logger_Log_Startup_messages() const
AP::logger().Write_Message(buffer); AP::logger().Write_Message(buffer);
} }
bool AP_GPS_Backend::should_df_log() const bool AP_GPS_Backend::should_log() const
{ {
return gps.should_df_log(); return gps.should_log();
} }

2
libraries/AP_GPS/GPS_Backend.h

@ -87,7 +87,7 @@ protected:
void _detection_message(char *buffer, uint8_t buflen) const; void _detection_message(char *buffer, uint8_t buflen) const;
bool should_df_log() const; bool should_log() const;
/* /*
set a timestamp based on arrival time on uart at current byte, set a timestamp based on arrival time on uart at current byte,

Loading…
Cancel
Save