|
|
@ -40,13 +40,16 @@ void Sub::init_ardupilot() |
|
|
|
switch (AP_BoardConfig::get_board_type()) { |
|
|
|
switch (AP_BoardConfig::get_board_type()) { |
|
|
|
case AP_BoardConfig::PX4_BOARD_PIXHAWK2: |
|
|
|
case AP_BoardConfig::PX4_BOARD_PIXHAWK2: |
|
|
|
AP_Param::set_by_name("GND_EXT_BUS", 0); |
|
|
|
AP_Param::set_by_name("GND_EXT_BUS", 0); |
|
|
|
|
|
|
|
celsius.init(0); |
|
|
|
break; |
|
|
|
break; |
|
|
|
default: |
|
|
|
default: |
|
|
|
AP_Param::set_by_name("GND_EXT_BUS", 1); |
|
|
|
AP_Param::set_by_name("GND_EXT_BUS", 1); |
|
|
|
|
|
|
|
celsius.init(1); |
|
|
|
break; |
|
|
|
break; |
|
|
|
} |
|
|
|
} |
|
|
|
#else |
|
|
|
#else |
|
|
|
AP_Param::set_default_by_name("GND_EXT_BUS", 1); |
|
|
|
AP_Param::set_default_by_name("GND_EXT_BUS", 1); |
|
|
|
|
|
|
|
celsius.init(1); |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
|
|
// identify ourselves correctly with the ground station
|
|
|
|
// identify ourselves correctly with the ground station
|
|
|
@ -71,8 +74,6 @@ void Sub::init_ardupilot() |
|
|
|
|
|
|
|
|
|
|
|
barometer.init(); |
|
|
|
barometer.init(); |
|
|
|
|
|
|
|
|
|
|
|
celsius.init(); |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// Register the mavlink service callback. This will run
|
|
|
|
// Register the mavlink service callback. This will run
|
|
|
|
// anytime there are more than 5ms remaining in a call to
|
|
|
|
// anytime there are more than 5ms remaining in a call to
|
|
|
|
// hal.scheduler->delay.
|
|
|
|
// hal.scheduler->delay.
|
|
|
|