mirror of https://github.com/ArduPilot/ardupilot
AHRS: added AHRS_GPS_USE parameter
this allows for the GPS to be disables for position updates, which allows for testing dead-reckoning
This commit is contained in:
parent
3b9623a44c
commit
3a92509b18
|
@ -52,6 +52,12 @@ const AP_Param::GroupInfo AP_AHRS_DCM::var_info[] PROGMEM = {
|
|||
// @Increment: .01
|
||||
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS_DCM, gps_gain, 1.0),
|
||||
|
||||
// @Param: GPS_USE
|
||||
// @DisplayName: enable/disable use of GPS for position estimation
|
||||
// @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_DCM, _gps_use, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -299,7 +305,7 @@ AP_AHRS_DCM::_P_gain(float spin_rate)
|
|||
// return true if we have and should use GPS
|
||||
bool AP_AHRS_DCM::have_gps(void)
|
||||
{
|
||||
if (!_gps || _gps->status() != GPS::GPS_OK) {
|
||||
if (!_gps || _gps->status() != GPS::GPS_OK || !_gps_use) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
|
|
|
@ -50,6 +50,9 @@ public:
|
|||
AP_Float _kp;
|
||||
AP_Float gps_gain;
|
||||
|
||||
// allow for runtime disabling of GPS usage for position
|
||||
AP_Int8 _gps_use;
|
||||
|
||||
// for holding parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
@ -127,7 +130,7 @@ private:
|
|||
Vector3f _last_fuse;
|
||||
Vector3f _last_vel;
|
||||
uint32_t _last_wind_time;
|
||||
float _last_airspeed;
|
||||
float _last_airspeed;
|
||||
};
|
||||
|
||||
#endif // AP_AHRS_DCM_H
|
||||
|
|
Loading…
Reference in New Issue