mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-27 02:04:00 -04:00
AP_GPS: disable SBP driver on APM2
the driver uses double precision floating point, which can't work on 8bit AVR with gcc
This commit is contained in:
parent
5a585b90e8
commit
43ebd86bb1
@ -166,11 +166,13 @@ AP_GPS::detect_instance(uint8_t instance)
|
||||
hal.console->print_P(PSTR(" MTK "));
|
||||
new_gps = new AP_GPS_MTK(*this, state[instance], port);
|
||||
}
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SBP) &&
|
||||
AP_GPS_SBP::_detect(dstate->sbp_detect_state, data)) {
|
||||
hal.console->print_P(PSTR(" SBP "));
|
||||
new_gps = new AP_GPS_SBP(*this, state[instance], port);
|
||||
}
|
||||
#endif // HAL_CPU_CLASS
|
||||
#if !defined( __AVR_ATmega1280__ )
|
||||
// save a bit of code space on a 1280
|
||||
else if ((_type[instance] == GPS_TYPE_AUTO || _type[instance] == GPS_TYPE_SIRF) &&
|
||||
|
@ -302,7 +302,9 @@ private:
|
||||
struct MTK19_detect_state mtk19_detect_state;
|
||||
struct SIRF_detect_state sirf_detect_state;
|
||||
struct NMEA_detect_state nmea_detect_state;
|
||||
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_75
|
||||
struct SBP_detect_state sbp_detect_state;
|
||||
#endif
|
||||
} detect_state[GPS_MAX_INSTANCES];
|
||||
|
||||
struct {
|
||||
|
Loading…
Reference in New Issue
Block a user