mirror of https://github.com/ArduPilot/ardupilot
AHRS: added AHRS_BARO_USE parameter
allow disabling of the use of the barometer for vertical acceleration compensation
This commit is contained in:
parent
4a942bc45d
commit
715541b508
|
@ -22,7 +22,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
|
||||||
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0),
|
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0),
|
||||||
|
|
||||||
// @Param: GPS_USE
|
// @Param: GPS_USE
|
||||||
// @DisplayName: enable/disable use of GPS for position estimation
|
// @DisplayName: AHRS use GPS
|
||||||
// @Description: This controls how how much to use the GPS to correct the attitude. This is for testing the dead-reckoning code
|
// @Description: This controls how how much to use the GPS to correct the attitude. This is for testing the dead-reckoning code
|
||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, 1),
|
AP_GROUPINFO("GPS_USE", 3, AP_AHRS, _gps_use, 1),
|
||||||
|
@ -49,6 +49,13 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
|
||||||
// @Increment: 1
|
// @Increment: 1
|
||||||
AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0),
|
AP_GROUPINFO("WIND_MAX", 6, AP_AHRS, _wind_max, 0.0),
|
||||||
|
|
||||||
|
// @Param: BARO_USE
|
||||||
|
// @DisplayName: AHRS Use Barometer
|
||||||
|
// @Description: This controls the use of the barometer for vertical acceleration compensation in AHRS
|
||||||
|
// @Values: 0:Disabled,1:Enabled
|
||||||
|
// @User: Advanced
|
||||||
|
AP_GROUPINFO("BARO_USE", 7, AP_AHRS, _baro_use, 1),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -143,6 +143,7 @@ public:
|
||||||
AP_Float _kp;
|
AP_Float _kp;
|
||||||
AP_Float gps_gain;
|
AP_Float gps_gain;
|
||||||
AP_Int8 _gps_use;
|
AP_Int8 _gps_use;
|
||||||
|
AP_Int8 _baro_use;
|
||||||
AP_Int8 _wind_max;
|
AP_Int8 _wind_max;
|
||||||
|
|
||||||
// for holding parameters
|
// for holding parameters
|
||||||
|
|
|
@ -446,18 +446,15 @@ AP_AHRS_DCM::drift_correction(float deltat)
|
||||||
_last_airspeed = airspeed.length();
|
_last_airspeed = airspeed.length();
|
||||||
}
|
}
|
||||||
|
|
||||||
#define USE_BAROMETER_FOR_VERTICAL_VELOCITY 1
|
|
||||||
#if USE_BAROMETER_FOR_VERTICAL_VELOCITY
|
|
||||||
/*
|
/*
|
||||||
* The barometer for vertical velocity is only enabled if we got
|
* The barometer for vertical velocity is only enabled if we got
|
||||||
* at least 5 pressure samples for the reading. This ensures we
|
* at least 5 pressure samples for the reading. This ensures we
|
||||||
* don't use very noisy climb rate data
|
* don't use very noisy climb rate data
|
||||||
*/
|
*/
|
||||||
if (_barometer != NULL && _barometer->get_pressure_samples() >= 5) {
|
if (_baro_use && _barometer != NULL && _barometer->get_pressure_samples() >= 5) {
|
||||||
// Z velocity is down
|
// Z velocity is down
|
||||||
velocity.z = -_barometer->get_climb_rate();
|
velocity.z = -_barometer->get_climb_rate();
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
// see if this is our first time through - in which case we
|
// see if this is our first time through - in which case we
|
||||||
// just setup the start times and return
|
// just setup the start times and return
|
||||||
|
|
Loading…
Reference in New Issue