Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Stop passing serial manager to GPS init #26551

Merged
merged 11 commits into from
Mar 18, 2024
2 changes: 1 addition & 1 deletion AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ void Tracker::init_ardupilot()

// GPS Initialization
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
gps.init();

ahrs.init();
ahrs.set_fly_forward(false);
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ void Copter::init_ardupilot()

// Do GPS init
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
gps.init();

AP::compass().set_log_bit(MASK_LOG_COMPASS);
AP::compass().init();
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ void Plane::init_ardupilot()

// GPS Initialization
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
gps.init();

init_rc_in(); // sets up rc channels from radio

Expand Down
2 changes: 1 addition & 1 deletion ArduSub/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ void Sub::init_ardupilot()

// Do GPS init
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
gps.init();

AP::compass().set_log_bit(MASK_LOG_COMPASS);
AP::compass().init();
Expand Down
2 changes: 1 addition & 1 deletion Blimp/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ void Blimp::init_ardupilot()

// Do GPS init
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
gps.init();

AP::compass().set_log_bit(MASK_LOG_COMPASS);
AP::compass().init();
Expand Down
2 changes: 1 addition & 1 deletion Rover/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ void Rover::init_ardupilot()

// Do GPS init
gps.set_log_gps_bit(MASK_LOG_GPS);
gps.init(serial_manager);
gps.init();

ins.set_log_raw_bit(MASK_LOG_IMU_RAW);

Expand Down
2 changes: 1 addition & 1 deletion Tools/AP_Periph/AP_Periph.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -148,7 +148,7 @@ void AP_Periph_FW::init()
#define MASK_LOG_GPS (1<<2)
gps.set_log_gps_bit(MASK_LOG_GPS);
#endif
gps.init(serial_manager);
gps.init();
}
#endif

Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_AHRS/examples/AHRS_Test/AHRS_Test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ void setup(void)
if (!AP::compass().read()) {
hal.console->printf("No compass detected\n");
}
AP::gps().init(serial_manager);
AP::gps().init();
}

void loop(void)
Expand Down
3 changes: 2 additions & 1 deletion libraries/AP_GPS/AP_GPS.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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()) {
Expand All @@ -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())) {
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/AP_GPS.h
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,7 @@ class AP_GPS
};

/// 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
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ void setup()

// Initialize the UART for GPS system
serial_manager.init();
gps.init(serial_manager);
gps.init();
}


Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Module/examples/ModuleTest/ModuleTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void setup(void)
baro.init();
ahrs.init();

gps.init(serial_manager);
gps.init();
}

void loop(void)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ void setup(void)
if(!AP::compass().read()) {
hal.console->printf("No compass detected\n");
}
AP::gps().init(serial_manager);
AP::gps().init();
AP::rtc().set_utc_usec(1546300800000, AP_RTC::source_type::SOURCE_GPS);
}

Expand Down
Loading