|
|
|
@ -44,8 +44,6 @@ extern const AP_HAL::HAL& hal;
@@ -44,8 +44,6 @@ extern const AP_HAL::HAL& hal;
|
|
|
|
|
#define UBLOX_HW_LOGGING 0 |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
bool AP_GPS_UBLOX::logging_started = false; |
|
|
|
|
|
|
|
|
|
AP_GPS_UBLOX::AP_GPS_UBLOX(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDriver *_port) : |
|
|
|
|
AP_GPS_Backend(_gps, _state, _port), |
|
|
|
|
_step(0), |
|
|
|
@ -249,53 +247,13 @@ AP_GPS_UBLOX::read(void)
@@ -249,53 +247,13 @@ AP_GPS_UBLOX::read(void)
|
|
|
|
|
// Private Methods /////////////////////////////////////////////////////////////
|
|
|
|
|
#if UBLOX_HW_LOGGING |
|
|
|
|
|
|
|
|
|
#define LOG_MSG_UBX1 200 |
|
|
|
|
#define LOG_MSG_UBX2 201 |
|
|
|
|
|
|
|
|
|
struct PACKED log_Ubx1 { |
|
|
|
|
LOG_PACKET_HEADER; |
|
|
|
|
uint32_t timestamp; |
|
|
|
|
uint8_t instance; |
|
|
|
|
uint16_t noisePerMS; |
|
|
|
|
uint8_t jamInd; |
|
|
|
|
uint8_t aPower; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
struct PACKED log_Ubx2 { |
|
|
|
|
LOG_PACKET_HEADER; |
|
|
|
|
uint32_t timestamp; |
|
|
|
|
uint8_t instance; |
|
|
|
|
int8_t ofsI; |
|
|
|
|
uint8_t magI; |
|
|
|
|
int8_t ofsQ; |
|
|
|
|
uint8_t magQ; |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
static const struct LogStructure ubx_log_structures[] PROGMEM = { |
|
|
|
|
{ LOG_MSG_UBX1, sizeof(log_Ubx1), |
|
|
|
|
"UBX1", "IBHBB", "TimeMS,Instance,noisePerMS,jamInd,aPower" }, |
|
|
|
|
{ LOG_MSG_UBX2, sizeof(log_Ubx2), |
|
|
|
|
"UBX2", "IBbBbB", "TimeMS,Instance,ofsI,magI,ofsQ,magQ" } |
|
|
|
|
}; |
|
|
|
|
|
|
|
|
|
void AP_GPS_UBLOX::write_logging_headers(void) |
|
|
|
|
{ |
|
|
|
|
if (!logging_started) { |
|
|
|
|
logging_started = true; |
|
|
|
|
gps._DataFlash->AddLogFormats(ubx_log_structures, 2); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void AP_GPS_UBLOX::log_mon_hw(void) |
|
|
|
|
{ |
|
|
|
|
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
// log mon_hw message
|
|
|
|
|
write_logging_headers(); |
|
|
|
|
|
|
|
|
|
struct log_Ubx1 pkt = { |
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_MSG_UBX1), |
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_UBX1_MSG), |
|
|
|
|
timestamp : hal.scheduler->millis(), |
|
|
|
|
instance : state.instance, |
|
|
|
|
noisePerMS : _buffer.mon_hw_60.noisePerMS, |
|
|
|
@ -315,11 +273,9 @@ void AP_GPS_UBLOX::log_mon_hw2(void)
@@ -315,11 +273,9 @@ void AP_GPS_UBLOX::log_mon_hw2(void)
|
|
|
|
|
if (gps._DataFlash == NULL || !gps._DataFlash->logging_started()) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
// log mon_hw message
|
|
|
|
|
write_logging_headers(); |
|
|
|
|
|
|
|
|
|
struct log_Ubx2 pkt = { |
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_MSG_UBX2), |
|
|
|
|
LOG_PACKET_HEADER_INIT(LOG_UBX2_MSG), |
|
|
|
|
timestamp : hal.scheduler->millis(), |
|
|
|
|
instance : state.instance, |
|
|
|
|
ofsI : _buffer.mon_hw2.ofsI, |
|
|
|
|