mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: Remove NMEA init blobs for binary drivers
All of the init strings that were sent in the NMEA driver are for GPS protocols which have binary drivers, which provide far more features and are more robust. It also appears that due to driver changes the config strings for SIRF/UBLOX were no longer correct anyways).
This commit is contained in:
parent
78a0298af0
commit
2f8f2ffd2d
|
@ -45,51 +45,6 @@ extern const AP_HAL::HAL& hal;
|
|||
#include <stdio.h>
|
||||
#endif
|
||||
|
||||
// SiRF init messages //////////////////////////////////////////////////////////
|
||||
//
|
||||
// Note that we will only see a SiRF in NMEA mode if we are explicitly configured
|
||||
// for NMEA. GPS_AUTO will try to set any SiRF unit to binary mode as part of
|
||||
// the autodetection process.
|
||||
//
|
||||
#define SIRF_INIT_MSG \
|
||||
"$PSRF103,0,0,1,1*25\r\n" /* GGA @ 1Hz */ \
|
||||
"$PSRF103,1,0,0,1*25\r\n" /* GLL off */ \
|
||||
"$PSRF103,2,0,0,1*26\r\n" /* GSA off */ \
|
||||
"$PSRF103,3,0,0,1*27\r\n" /* GSV off */ \
|
||||
"$PSRF103,4,0,1,1*20\r\n" /* RMC off */ \
|
||||
"$PSRF103,5,0,1,1*20\r\n" /* VTG @ 1Hz */ \
|
||||
"$PSRF103,6,0,0,1*22\r\n" /* MSS off */ \
|
||||
"$PSRF103,8,0,0,1*2C\r\n" /* ZDA off */ \
|
||||
"$PSRF151,1*3F\r\n" /* WAAS on (not always supported) */ \
|
||||
"$PSRF106,21*0F\r\n" /* datum = WGS84 */
|
||||
|
||||
// MediaTek init messages //////////////////////////////////////////////////////
|
||||
//
|
||||
// Note that we may see a MediaTek in NMEA mode if we are connected to a non-DIYDrones
|
||||
// MediaTek-based GPS.
|
||||
//
|
||||
#define MTK_INIT_MSG \
|
||||
"$PMTK314,0,1,1,1,0,0,0,0,0,0,0,0,0,0,0,0,0*29\r\n" /* RMC, GGA & VTG once every fix */ \
|
||||
"$PMTK330,0*2E\r\n" /* datum = WGS84 */ \
|
||||
"$PMTK313,1*2E\r\n" /* SBAS on */ \
|
||||
"$PMTK301,2*2E\r\n" /* use SBAS data for DGPS */
|
||||
|
||||
// ublox init messages /////////////////////////////////////////////////////////
|
||||
//
|
||||
// Note that we will only see a ublox in NMEA mode if we are explicitly configured
|
||||
// for NMEA. GPS_AUTO will try to set any ublox unit to binary mode as part of
|
||||
// the autodetection process.
|
||||
//
|
||||
// We don't attempt to send $PUBX,41 as the unit must already be talking NMEA
|
||||
// and we don't know the baudrate.
|
||||
//
|
||||
#define UBLOX_INIT_MSG \
|
||||
"$PUBX,40,gga,0,1,0,0,0,0*7B\r\n" /* GGA on at one per fix */ \
|
||||
"$PUBX,40,vtg,0,1,0,0,0,0*7F\r\n" /* VTG on at one per fix */ \
|
||||
"$PUBX,40,rmc,0,0,0,0,0,0*67\r\n" /* RMC off (XXX suppress other message types?) */
|
||||
|
||||
const char AP_GPS_NMEA::_initialisation_blob[] = SIRF_INIT_MSG MTK_INIT_MSG UBLOX_INIT_MSG;
|
||||
|
||||
// Convenience macros //////////////////////////////////////////////////////////
|
||||
//
|
||||
#define DIGIT_TO_VAL(_x) (_x - '0')
|
||||
|
@ -104,7 +59,6 @@ AP_GPS_NMEA::AP_GPS_NMEA(AP_GPS &_gps, AP_GPS::GPS_State &_state, AP_HAL::UARTDr
|
|||
_term_offset(0),
|
||||
_gps_data_good(false)
|
||||
{
|
||||
gps.send_blob_start(state.instance, _initialisation_blob, sizeof(_initialisation_blob));
|
||||
// this guarantees that _term is always nul terminated
|
||||
memset(_term, 0, sizeof(_term));
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue