mirror of https://github.com/ArduPilot/ardupilot
AP_GPS: stop passing serial manager to GPS init
it can get this via the singleton
This commit is contained in:
parent
4811a10e1a
commit
8bd05941a1
|
@ -464,7 +464,7 @@ bool AP_GPS::needs_uart(GPS_Type type) const
|
|||
}
|
||||
|
||||
/// Startup initialisation.
|
||||
void AP_GPS::init(const AP_SerialManager& serial_manager)
|
||||
void AP_GPS::init()
|
||||
{
|
||||
// Set new primary param based on old auto_switch use second option
|
||||
if ((_auto_switch.get() == 3) && !_primary.configured()) {
|
||||
|
@ -473,6 +473,7 @@ void AP_GPS::init(const AP_SerialManager& serial_manager)
|
|||
}
|
||||
|
||||
// search for serial ports with gps protocol
|
||||
const auto &serial_manager = AP::serialmanager();
|
||||
uint8_t uart_idx = 0;
|
||||
for (uint8_t i=0; i<GPS_MAX_RECEIVERS; i++) {
|
||||
if (needs_uart((GPS_Type)_type[i].get())) {
|
||||
|
|
|
@ -243,7 +243,7 @@ public:
|
|||
};
|
||||
|
||||
/// Startup initialisation.
|
||||
void init(const class AP_SerialManager& serial_manager);
|
||||
void init();
|
||||
|
||||
/// Update GPS state based on possible bytes received from the module.
|
||||
/// This routine must be called periodically (typically at 10Hz or
|
||||
|
|
|
@ -66,7 +66,7 @@ void setup()
|
|||
|
||||
// Initialize the UART for GPS system
|
||||
serial_manager.init();
|
||||
gps.init(serial_manager);
|
||||
gps.init();
|
||||
}
|
||||
|
||||
|
||||
|
|
Loading…
Reference in New Issue