Plane: more fixes for SITL and new AP_Param startup
This commit is contained in:
parent
8916b280fd
commit
678947c65d
@ -151,6 +151,7 @@ static AP_ADC_ADS7844 adc;
|
||||
# if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
AP_Baro_BMP085_HIL barometer;
|
||||
AP_Compass_HIL compass;
|
||||
AP_InertialSensor_Stub ins;
|
||||
#else
|
||||
|
||||
#if CONFIG_BARO == AP_BARO_BMP085
|
||||
@ -190,7 +191,7 @@ AP_GPS_None g_gps_driver(NULL);
|
||||
|
||||
# if CONFIG_INS_TYPE == CONFIG_INS_MPU6000
|
||||
AP_InertialSensor_MPU6000 ins;
|
||||
# else
|
||||
# elif CONFIG_HAL_BOARD != HAL_BOARD_AVR_SITL
|
||||
AP_InertialSensor_Oilpan ins( &adc );
|
||||
#endif // CONFIG_INS_TYPE
|
||||
|
||||
@ -643,11 +644,14 @@ AP_Mount camera_mount2(¤t_loc, g_gps, &ahrs, 1);
|
||||
// Top-level logic
|
||||
////////////////////////////////////////////////////////////////////////////////
|
||||
|
||||
// setup the var_info table
|
||||
AP_Param param_loader(var_info, WP_START_BYTE);
|
||||
|
||||
void setup() {
|
||||
cliSerial = hal.console;
|
||||
|
||||
// setup the default values of variables listed in var_info[]
|
||||
AP_Param::setup_sketch_defaults(var_info, WP_START_BYTE);
|
||||
// load the default values of variables listed in var_info[]
|
||||
AP_Param::setup_sketch_defaults();
|
||||
|
||||
rssi_analog_source = hal.analogin->channel(ANALOG_INPUT_NONE, 0.25);
|
||||
|
||||
|
@ -446,7 +446,7 @@ static void NOINLINE send_ahrs(mavlink_channel_t chan)
|
||||
ahrs.get_error_yaw());
|
||||
}
|
||||
|
||||
#ifdef DESKTOP_BUILD
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
// report simulator state
|
||||
static void NOINLINE send_simstate(mavlink_channel_t chan)
|
||||
{
|
||||
@ -459,7 +459,7 @@ static void NOINLINE send_hwstatus(mavlink_channel_t chan)
|
||||
mavlink_msg_hwstatus_send(
|
||||
chan,
|
||||
board_voltage(),
|
||||
#ifdef DESKTOP_BUILD
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
0);
|
||||
#else
|
||||
hal.i2c->lockup_count());
|
||||
@ -642,7 +642,7 @@ static bool mavlink_try_send_message(mavlink_channel_t chan, enum ap_message id,
|
||||
break;
|
||||
|
||||
case MSG_SIMSTATE:
|
||||
#ifdef DESKTOP_BUILD
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
CHECK_PAYLOAD_SIZE(SIMSTATE);
|
||||
send_simstate(chan);
|
||||
#endif
|
||||
|
@ -684,7 +684,7 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GOBJECT(camera_mount2, "MNT2_", AP_Mount),
|
||||
#endif
|
||||
|
||||
#ifdef DESKTOP_BUILD
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_AVR_SITL
|
||||
// @Group: SIM_
|
||||
// @Path: ../libraries/SITL/SITL.cpp
|
||||
GOBJECT(sitl, "SIM_", SITL),
|
||||
|
Loading…
Reference in New Issue
Block a user