AP_GPS: allow UBLOX driver to be compiled out

This commit is contained in:
Peter Barker 2022-04-10 10:07:37 +10:00 committed by Andrew Tridgell
parent e858a0fab7
commit b88f414320
3 changed files with 26 additions and 3 deletions

View File

@ -73,12 +73,15 @@ extern const AP_HAL::HAL &hal;
const uint32_t AP_GPS::_baudrates[] = {9600U, 115200U, 4800U, 19200U, 38400U, 57600U, 230400U, 460800U};
// initialisation blobs to send to the GPS to try to get it into the
// right mode
// right mode.
const char AP_GPS::_initialisation_blob[] =
#if AP_GPS_UBLOX_ENABLED
UBLOX_SET_BINARY_230400
#endif
#if AP_GPS_SIRF_ENABLED
SIRF_SET_BINARY
#endif
"" // to compile we need *some_initialiser if all backends compiled out
;
AP_GPS *AP_GPS::_singleton;
@ -560,13 +563,15 @@ void AP_GPS::send_blob_start(uint8_t instance, const char *_blob, uint16_t size)
*/
void AP_GPS::send_blob_start(uint8_t instance)
{
#if AP_GPS_UBLOX_ENABLED
if (_type[instance] == GPS_TYPE_UBLOX && option_set(DriverOptions::UBX_Use115200)) {
static const char blob[] = UBLOX_SET_BINARY_115200;
send_blob_start(instance, blob, sizeof(blob));
return;
}
#endif // AP_GPS_UBLOX_ENABLED
#if GPS_MOVING_BASELINE
#if GPS_MOVING_BASELINE && AP_GPS_UBLOX_ENABLED
if ((_type[instance] == GPS_TYPE_UBLOX_RTK_BASE ||
_type[instance] == GPS_TYPE_UBLOX_RTK_ROVER) &&
!option_set(DriverOptions::UBX_MBUseUart2)) {
@ -587,6 +592,9 @@ void AP_GPS::send_blob_start(uint8_t instance)
}
#endif // AP_GPS_NMEA_ENABLED
// send combined initialisation blob, on the assumption that the
// GPS units will parse what they need and ignore the data they
// don't understand:
send_blob_start(instance, _initialisation_blob, sizeof(_initialisation_blob));
}
@ -746,6 +754,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
for.
*/
#if AP_GPS_UBLOX_ENABLED
if ((_type[instance] == GPS_TYPE_AUTO ||
_type[instance] == GPS_TYPE_UBLOX) &&
((!_auto_config && _baudrates[dstate->current_baud] >= 38400) ||
@ -768,6 +777,7 @@ AP_GPS_Backend *AP_GPS::_detect_instance(uint8_t instance)
}
return new AP_GPS_UBLOX(*this, state[instance], _port[instance], role);
}
#endif // AP_GPS_UBLOX_ENABLED
#if AP_GPS_SBP2_ENABLED
if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
AP_GPS_SBP2::_detect(dstate->sbp2_detect_state, data)) {

View File

@ -18,8 +18,11 @@
// Origin code by Michael Smith, Jordi Munoz and Jose Julio, DIYDrones.com
// Substantially rewritten for new GPS driver structure by Andrew Tridgell
//
#include "AP_GPS.h"
#include "AP_GPS_UBLOX.h"
#if AP_GPS_UBLOX_ENABLED
#include "AP_GPS.h"
#include <AP_HAL/Util.h>
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS.h>
@ -2033,3 +2036,5 @@ bool AP_GPS_UBLOX::supports_F9_config(void) const
{
return _hardware_generation == UBLOX_F9 && _hardware_generation != UBLOX_UNKNOWN_HARDWARE_GENERATION;
}
#endif

View File

@ -22,6 +22,12 @@
#include <AP_HAL/AP_HAL.h>
#ifndef AP_GPS_UBLOX_ENABLED
#define AP_GPS_UBLOX_ENABLED 1
#endif
#if AP_GPS_UBLOX_ENABLED
#include "AP_GPS.h"
#include "GPS_Backend.h"
@ -809,3 +815,5 @@ private:
RTCM3_Parser *rtcm3_parser;
#endif // GPS_MOVING_BASELINE
};
#endif