mirror of https://github.com/ArduPilot/ardupilot
AP_GPS:make Unicore reset to rover in all cases
This commit is contained in:
parent
77540dff07
commit
eeb72637ec
|
@ -859,8 +859,7 @@ void AP_GPS_NMEA::send_config(void)
|
|||
switch (get_type()) {
|
||||
#if AP_GPS_NMEA_UNICORE_ENABLED
|
||||
case AP_GPS::GPS_TYPE_UNICORE_MOVINGBASE_NMEA:
|
||||
port->printf("\r\nMODE MOVINGBASE\r\n" \
|
||||
"CONFIG HEADING FIXLENGTH\r\n" \
|
||||
port->printf("\r\nCONFIG HEADING FIXLENGTH\r\n" \
|
||||
"CONFIG UNDULATION AUTO\r\n" \
|
||||
"CONFIG\r\n" \
|
||||
"UNIHEADINGA %.3f\r\n",
|
||||
|
@ -870,6 +869,7 @@ void AP_GPS_NMEA::send_config(void)
|
|||
|
||||
case AP_GPS::GPS_TYPE_UNICORE_NMEA: {
|
||||
port->printf("\r\nAGRICA %.3f\r\n" \
|
||||
"MODE MOVINGBASE\r\n" \
|
||||
"GNGGA %.3f\r\n" \
|
||||
"GNRMC %.3f\r\n",
|
||||
rate_s, rate_s, rate_s);
|
||||
|
|
Loading…
Reference in New Issue