GPS_UBLOX: fixed auto-config of baudrate
this fixes the setting of the baudrate on a uBlox that is configured for 9600. It fixes the NMEA message to have a \r\n, plus sends the NAV_SOL rate config before the NMEA baudrate config message. This fixes issue #159
This commit is contained in:
parent
fdcb78ccf7
commit
551950c573
@ -49,7 +49,9 @@ AP_GPS_Auto::read(void)
|
||||
if (now - last_baud_change_ms > 1200) {
|
||||
// its been more than 1.2 seconds without detection on this
|
||||
// GPS - switch to another baud rate
|
||||
_port->begin(pgm_read_dword(&baudrates[last_baud]), 256, 16);
|
||||
_baudrate = pgm_read_dword(&baudrates[last_baud]);
|
||||
//hal.console->printf_P(PSTR("Setting GPS baudrate %u\n"), (unsigned)_baudrate);
|
||||
_port->begin(_baudrate, 256, 16);
|
||||
last_baud++;
|
||||
last_baud_change_ms = now;
|
||||
if (last_baud == sizeof(baudrates) / sizeof(baudrates[0])) {
|
||||
@ -88,7 +90,14 @@ AP_GPS_Auto::_detect(void)
|
||||
|
||||
while (_port->available() > 0 && new_gps == NULL) {
|
||||
uint8_t data = _port->read();
|
||||
if (AP_GPS_UBLOX::_detect(data)) {
|
||||
/*
|
||||
running a uBlox at less than 38400 will lead to packet
|
||||
corruption, as we can't receive the packets in the 200ms
|
||||
window for 5Hz fixes. The NMEA startup message should force
|
||||
the uBlox into 38400 no matter what rate it is configured
|
||||
for.
|
||||
*/
|
||||
if (_baudrate >= 38400 && AP_GPS_UBLOX::_detect(data)) {
|
||||
hal.console->print_P(PSTR(" ublox "));
|
||||
new_gps = new AP_GPS_UBLOX();
|
||||
}
|
||||
|
@ -15,14 +15,18 @@
|
||||
#include "GPS.h"
|
||||
|
||||
/*
|
||||
* try to put a UBlox into binary mode. This is in two parts. First we
|
||||
* send a PUBX asking the UBlox to receive NMEA and UBX, and send UBX,
|
||||
* with a baudrate of 38400. Then we send a UBX message setting rate 1
|
||||
* for the NAV_SOL message. The setup of NAV_SOL is to cope with
|
||||
* configurations where all UBX binary message types are disabled.
|
||||
* try to put a UBlox into binary mode. This is in two parts.
|
||||
*
|
||||
* First we send a ubx binary message that enables the NAV_SOL message
|
||||
* at rate 1. Then we send a NMEA message to set the baud rate to our
|
||||
* desired rate. The reason for doing the NMEA message second is if we
|
||||
* send it first the second message will be ignored for a baud rate
|
||||
* change.
|
||||
* The reason we need the NAV_SOL rate message at all is some uBlox
|
||||
* modules are configured with all ubx binary messages off, which
|
||||
* would mean we would never detect it.
|
||||
*/
|
||||
|
||||
#define UBLOX_SET_BINARY "$PUBX,41,1,0003,0001,38400,0*26\n\265\142\006\001\003\000\001\006\001\022\117"
|
||||
#define UBLOX_SET_BINARY "\265\142\006\001\003\000\001\006\001\022\117$PUBX,41,1,0003,0001,38400,0*26\r\n"
|
||||
|
||||
class AP_GPS_UBLOX : public GPS
|
||||
{
|
||||
|
@ -160,6 +160,7 @@ void GPS::_update_progstr(void)
|
||||
if (nbytes > 16) {
|
||||
nbytes = 16;
|
||||
}
|
||||
//hal.console->printf_P(PSTR("writing %u bytes\n"), (unsigned)nbytes);
|
||||
_write_progstr_block(progstr_state.fs, q->pstr+q->ofs, nbytes);
|
||||
q->ofs += nbytes;
|
||||
if (q->ofs == q->size) {
|
||||
|
@ -206,6 +206,9 @@ protected:
|
||||
// does this GPS support raw velocity numbers?
|
||||
bool _have_raw_velocity;
|
||||
|
||||
// detected baudrate
|
||||
uint16_t _baudrate;
|
||||
|
||||
private:
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user