mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Rover: 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
78b2924c00
commit
a0d4feb216
@ -90,11 +90,20 @@ void Rover::init_ardupilot()
|
|||||||
|
|
||||||
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();
|
||||||
|
|
||||||
ServoRelayEvents.set_channel_mask(0xFFF0);
|
ServoRelayEvents.set_channel_mask(0xFFF0);
|
||||||
|
|
||||||
set_control_channels();
|
set_control_channels();
|
||||||
@ -114,7 +123,7 @@ void Rover::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);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -129,12 +138,6 @@ void Rover::init_ardupilot()
|
|||||||
log_init();
|
log_init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
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);
|
|
||||||
|
|
||||||
if (g.compass_enabled==true) {
|
if (g.compass_enabled==true) {
|
||||||
if (!compass.init()|| !compass.read()) {
|
if (!compass.init()|| !compass.read()) {
|
||||||
cliSerial->println("Compass initialisation failed!");
|
cliSerial->println("Compass initialisation failed!");
|
||||||
|
Loading…
Reference in New Issue
Block a user