Plane: 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
ba7d0d6cd8
commit
82382a7e9c
@ -113,12 +113,18 @@ void Plane::init_ardupilot()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
BoardConfig.init();
|
GCS_MAVLINK::set_dataflash(&DataFlash);
|
||||||
|
|
||||||
// initialise serial ports
|
// initialise serial ports
|
||||||
serial_manager.init();
|
serial_manager.init();
|
||||||
|
gcs[0].setup_uart(serial_manager, AP_SerialManager::SerialProtocol_MAVLink, 0);
|
||||||
|
|
||||||
GCS_MAVLINK::set_dataflash(&DataFlash);
|
// 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);
|
||||||
|
|
||||||
|
// setup any board specific drivers
|
||||||
|
BoardConfig.init();
|
||||||
|
|
||||||
// allow servo set on all channels except first 4
|
// allow servo set on all channels except first 4
|
||||||
ServoRelayEvents.set_channel_mask(0xFFF0);
|
ServoRelayEvents.set_channel_mask(0xFFF0);
|
||||||
@ -144,7 +150,7 @@ void Plane::init_ardupilot()
|
|||||||
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);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -184,10 +190,6 @@ void Plane::init_ardupilot()
|
|||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// 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);
|
|
||||||
|
|
||||||
// give AHRS the airspeed sensor
|
// give AHRS the airspeed sensor
|
||||||
ahrs.set_airspeed(&airspeed);
|
ahrs.set_airspeed(&airspeed);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user