mirror of https://github.com/ArduPilot/ardupilot
SITL: added SIM_BARO_DISABLE parameter
useful for testing baro failure
This commit is contained in:
parent
d37f1a1376
commit
7404fc9d40
|
@ -38,6 +38,11 @@ void SITL_State::_update_barometer(float altitude)
|
|||
return;
|
||||
}
|
||||
|
||||
if (_sitl->baro_disable) {
|
||||
// barometer is disabled
|
||||
return;
|
||||
}
|
||||
|
||||
// 80Hz, to match the real APM2 barometer
|
||||
uint32_t now = hal.scheduler->millis();
|
||||
if ((now - last_update) < 12) {
|
||||
|
|
|
@ -55,6 +55,7 @@ const AP_Param::GroupInfo SITL::var_info[] PROGMEM = {
|
|||
AP_GROUPINFO("SONAR_RND", 24, SITL, sonar_noise, 0),
|
||||
AP_GROUPINFO("RC_FAIL", 25, SITL, rc_fail, 0),
|
||||
AP_GROUPINFO("GPS2_ENABLE", 26, SITL, gps2_enable, 0),
|
||||
AP_GROUPINFO("BARO_DISABLE", 27, SITL, baro_disable, 0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
|
|
@ -75,6 +75,7 @@ public:
|
|||
AP_Float batt_voltage; // battery voltage base
|
||||
AP_Float accel_fail; // accelerometer failure value
|
||||
AP_Int8 rc_fail; // fail RC input
|
||||
AP_Int8 baro_disable; // disable simulated barometer
|
||||
|
||||
// wind control
|
||||
AP_Float wind_speed;
|
||||
|
|
Loading…
Reference in New Issue