mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: added logging to more serial GPS backends
This commit is contained in:
parent
6e3ca69ae6
commit
4a6673c04e
|
@ -57,6 +57,9 @@ AP_GPS_ERB::read(void)
|
||||||
|
|
||||||
// read the next byte
|
// read the next byte
|
||||||
data = port->read();
|
data = port->read();
|
||||||
|
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||||
|
log_data(&data, 1);
|
||||||
|
#endif
|
||||||
|
|
||||||
reset:
|
reset:
|
||||||
switch(_step) {
|
switch(_step) {
|
||||||
|
|
|
@ -76,6 +76,9 @@ AP_GPS_GSOF::read(void)
|
||||||
bool ret = false;
|
bool ret = false;
|
||||||
while (port->available() > 0) {
|
while (port->available() > 0) {
|
||||||
uint8_t temp = port->read();
|
uint8_t temp = port->read();
|
||||||
|
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||||
|
log_data(&temp, 1);
|
||||||
|
#endif
|
||||||
ret |= parse(temp);
|
ret |= parse(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -54,12 +54,12 @@ bool AP_GPS_NMEA::read(void)
|
||||||
numc = port->available();
|
numc = port->available();
|
||||||
while (numc--) {
|
while (numc--) {
|
||||||
char c = port->read();
|
char c = port->read();
|
||||||
if (_decode(c)) {
|
|
||||||
parsed = true;
|
|
||||||
}
|
|
||||||
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||||
log_data((const uint8_t *)&c, 1);
|
log_data((const uint8_t *)&c, 1);
|
||||||
#endif
|
#endif
|
||||||
|
if (_decode(c)) {
|
||||||
|
parsed = true;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return parsed;
|
return parsed;
|
||||||
}
|
}
|
||||||
|
|
|
@ -90,6 +90,9 @@ AP_GPS_NOVA::read(void)
|
||||||
bool ret = false;
|
bool ret = false;
|
||||||
while (port->available() > 0) {
|
while (port->available() > 0) {
|
||||||
uint8_t temp = port->read();
|
uint8_t temp = port->read();
|
||||||
|
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||||
|
log_data(&temp, 1);
|
||||||
|
#endif
|
||||||
ret |= parse(temp);
|
ret |= parse(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -86,6 +86,9 @@ AP_GPS_SBF::read(void)
|
||||||
uint32_t available_bytes = port->available();
|
uint32_t available_bytes = port->available();
|
||||||
for (uint32_t i = 0; i < available_bytes; i++) {
|
for (uint32_t i = 0; i < available_bytes; i++) {
|
||||||
uint8_t temp = port->read();
|
uint8_t temp = port->read();
|
||||||
|
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||||
|
log_data(&temp, 1);
|
||||||
|
#endif
|
||||||
ret |= parse(temp);
|
ret |= parse(temp);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -100,6 +100,9 @@ AP_GPS_SBP::_sbp_process()
|
||||||
|
|
||||||
while (port->available() > 0) {
|
while (port->available() > 0) {
|
||||||
uint8_t temp = port->read();
|
uint8_t temp = port->read();
|
||||||
|
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||||
|
log_data(&temp, 1);
|
||||||
|
#endif
|
||||||
uint16_t crc;
|
uint16_t crc;
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -103,6 +103,9 @@ AP_GPS_SBP2::_sbp_process()
|
||||||
while (nleft > 0) {
|
while (nleft > 0) {
|
||||||
nleft--;
|
nleft--;
|
||||||
uint8_t temp = port->read();
|
uint8_t temp = port->read();
|
||||||
|
#if AP_GPS_DEBUG_LOGGING_ENABLED
|
||||||
|
log_data(&temp, 1);
|
||||||
|
#endif
|
||||||
uint16_t crc;
|
uint16_t crc;
|
||||||
|
|
||||||
//This switch reads one character at a time,
|
//This switch reads one character at a time,
|
||||||
|
|
Loading…
Reference in New Issue