From 715541b508a6501612e811f7b7bd8fb1d3934f05 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 12 Sep 2012 14:42:04 +1000 Subject: [PATCH] AHRS: added AHRS_BARO_USE parameter allow disabling of the use of the barometer for vertical acceleration compensation --- libraries/AP_AHRS/AP_AHRS.cpp | 9 ++++++++- libraries/AP_AHRS/AP_AHRS.h | 1 + libraries/AP_AHRS/AP_AHRS_DCM.cpp | 5 +---- 3 files changed, 10 insertions(+), 5 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.cpp b/libraries/AP_AHRS/AP_AHRS.cpp index bae347e954..af36c5a571 100644 --- a/libraries/AP_AHRS/AP_AHRS.cpp +++ b/libraries/AP_AHRS/AP_AHRS.cpp @@ -22,7 +22,7 @@ const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = { AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, gps_gain, 1.0), // @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 // @User: Advanced 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 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 }; diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index a0e0a61e31..c9b5ce9e23 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -143,6 +143,7 @@ public: AP_Float _kp; AP_Float gps_gain; AP_Int8 _gps_use; + AP_Int8 _baro_use; AP_Int8 _wind_max; // for holding parameters diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index c01295e7be..5c884df841 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -446,18 +446,15 @@ AP_AHRS_DCM::drift_correction(float deltat) _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 * at least 5 pressure samples for the reading. This ensures we * 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 velocity.z = -_barometer->get_climb_rate(); } -#endif // see if this is our first time through - in which case we // just setup the start times and return