mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: changed startup order
this allows BoardConfig to report errors in a way that allows for BRD_TYPE to be changed by the user
This commit is contained in:
parent
a0d4feb216
commit
80bad445b8
@ -28,11 +28,20 @@ void Tracker::init_tracker()
|
|||||||
// Check the EEPROM format version before loading any parameters from EEPROM
|
// Check the EEPROM format version before loading any parameters from EEPROM
|
||||||
load_parameters();
|
load_parameters();
|
||||||
|
|
||||||
BoardConfig.init();
|
GCS_MAVLINK::set_dataflash(&DataFlash);
|
||||||
|
|
||||||
// initialise serial ports
|
// initialise serial ports
|
||||||
serial_manager.init();
|
serial_manager.init();
|
||||||
|
|
||||||
|
// setup first port early to allow BoardConfig to report errors
|
||||||
|
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||||
|
|
||||||
|
// Register mavlink_delay_cb, which will run anytime you have
|
||||||
|
// more than 5ms remaining in your call to hal.scheduler->delay
|
||||||
|
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
||||||
|
|
||||||
|
BoardConfig.init();
|
||||||
|
|
||||||
// init baro before we start the GCS, so that the CLI baro test works
|
// init baro before we start the GCS, so that the CLI baro test works
|
||||||
barometer.init();
|
barometer.init();
|
||||||
|
|
||||||
@ -42,23 +51,17 @@ void Tracker::init_tracker()
|
|||||||
check_usb_mux();
|
check_usb_mux();
|
||||||
|
|
||||||
// setup telem slots with serial ports
|
// setup telem slots with serial ports
|
||||||
for (uint8_t i = 0; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
for (uint8_t i = 1; i < MAVLINK_COMM_NUM_BUFFERS; i++) {
|
||||||
gcs[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
gcs[i].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, i);
|
||||||
gcs[i].set_snoop(mavlink_snoop_static);
|
gcs[i].set_snoop(mavlink_snoop_static);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Register mavlink_delay_cb, which will run anytime you have
|
|
||||||
// more than 5ms remaining in your call to hal.scheduler->delay
|
|
||||||
hal.scheduler->register_delay_callback(mavlink_delay_cb_static, 5);
|
|
||||||
|
|
||||||
mavlink_system.sysid = g.sysid_this_mav;
|
mavlink_system.sysid = g.sysid_this_mav;
|
||||||
|
|
||||||
#if LOGGING_ENABLED == ENABLED
|
#if LOGGING_ENABLED == ENABLED
|
||||||
log_init();
|
log_init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
GCS_MAVLINK::set_dataflash(&DataFlash);
|
|
||||||
|
|
||||||
if (g.compass_enabled==true) {
|
if (g.compass_enabled==true) {
|
||||||
if (!compass.init() || !compass.read()) {
|
if (!compass.init() || !compass.read()) {
|
||||||
hal.console->println("Compass initialisation failed!");
|
hal.console->println("Compass initialisation failed!");
|
||||||
|
Loading…
Reference in New Issue
Block a user