AHRS: moved var_info[] into top level AP_AHRS class

This commit is contained in:
Andrew Tridgell 2012-08-21 15:58:09 +10:00
parent 1b0f5ac84f
commit 134cd51d17
7 changed files with 54 additions and 75 deletions

View File

@ -0,0 +1,45 @@
/*
APM_AHRS.cpp
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public License
as published by the Free Software Foundation; either version 2.1
of the License, or (at your option) any later version.
*/
#include <FastSerial.h>
#include <AP_AHRS.h>
// table of user settable parameters
const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
// index 0 and 1 are for old parameters that are no longer used
// @Param: GPS_GAIN
// @DisplayName: AHRS GPS gain
// @Description: This controls how how much to use the GPS to correct the attitude
// @Range: 0.0 1.0
// @Increment: .01
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS, 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, _gps_use, 1),
// @Param: YAW_P
// @DisplayName: Yaw P
// @Description: This controls the weight the compass has on the overall heading
// @Range: 0 .4
// @Increment: .01
AP_GROUPINFO("YAW_P", 4, AP_AHRS, _kp_yaw, 0.4),
// @Param: RP_P
// @DisplayName: AHRS RP_P
// @Description: This controls how fast the accelerometers correct the attitude
// @Range: 0 .4
// @Increment: .01
AP_GROUPINFO("RP_P", 5, AP_AHRS, _kp, 0.4),
AP_GROUPEND
};

View File

@ -117,6 +117,15 @@ public:
_fast_ground_gains = setting;
}
// settable parameters
AP_Float _kp_yaw;
AP_Float _kp;
AP_Float gps_gain;
AP_Int8 _gps_use;
// for holding parameters
static const struct AP_Param::GroupInfo var_info[];
protected:
// whether the yaw value has been intialised with a reference
bool _have_initial_yaw;

View File

@ -29,39 +29,6 @@
// http://gentlenav.googlecode.com/files/fastRotations.pdf
#define SPIN_RATE_LIMIT 20
// table of user settable parameters
const AP_Param::GroupInfo AP_AHRS_DCM::var_info[] PROGMEM = {
// index 0 and 1 are for old parameters that are no longer used
// @Param: GPS_GAIN
// @DisplayName: AHRS GPS gain
// @Description: This controls how how much to use the GPS to correct the attitude
// @Range: 0.0 1.0
// @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),
// @Param: YAW_P
// @DisplayName: Yaw P
// @Description: This controls the weight the compass has on the overall heading
// @Range: 0 .4
// @Increment: .01
AP_GROUPINFO("YAW_P", 4, AP_AHRS_DCM, _kp_yaw, 0.4),
// @Param: RP_P
// @DisplayName: AHRS RP_P
// @Description: This controls how fast the accelerometers correct the attitude
// @Range: 0 .4
// @Increment: .01
AP_GROUPINFO("RP_P", 5, AP_AHRS_DCM, _kp, 0.4),
AP_GROUPEND
};
// run a full DCM update round
void

View File

@ -22,9 +22,6 @@ public:
// with large drift levels
_ki = 0.0087;
_ki_yaw = 0.01;
_kp.set(0.4);
_kp_yaw.set(0.4);
gps_gain.set(1.0);
}
// return the smoothed gyro vector corrected for drift
@ -45,11 +42,6 @@ public:
float get_error_rp(void);
float get_error_yaw(void);
// settable parameters
AP_Float _kp_yaw;
AP_Float _kp;
AP_Float gps_gain;
// allow for runtime disabling of GPS usage for position
AP_Int8 _gps_use;
@ -58,9 +50,6 @@ public:
return _wind;
}
// for holding parameters
static const struct AP_Param::GroupInfo var_info[];
private:
float _ki;
float _ki_yaw;

View File

@ -32,11 +32,6 @@ public:
float get_error_rp(void) { return 0; }
float get_error_yaw(void) { return 0; }
// settable parameters
AP_Float _kp;
AP_Float _kp_yaw;
AP_Float gps_gain;
private:
Vector3f _omega;
};

View File

@ -27,24 +27,6 @@
// http://gentlenav.googlecode.com/files/fastRotations.pdf
#define SPIN_RATE_LIMIT 20
// table of user settable parameters
const AP_Param::GroupInfo AP_AHRS_MPU6000::var_info[] PROGMEM = {
// @Param: AHRS_YAW_P
// @DisplayName: Yaw P
// @Description: This controls the weight the compass has on the overall heading
// @Range: 0 .4
// @Increment: .01
AP_GROUPINFO("YAW_P", 0, AP_AHRS_MPU6000, _kp_yaw, 0.4),
// @Param: AHRS_RP_P
// @DisplayName: AHRS RP_P
// @Description: This controls how fast the accelerometers correct the attitude
// @Range: 0 .4
// @Increment: .01
AP_GROUPINFO("RP_P", 1, AP_AHRS_MPU6000, _kp, 0.4),
AP_GROUPEND
};
void
AP_AHRS_MPU6000::init()
{

View File

@ -56,14 +56,6 @@ public:
float get_error_rp(void);
float get_error_yaw(void);
// settable parameters
AP_Float _kp_yaw;
AP_Float _kp;
AP_Float gps_gain; // not currently supported
// for holding parameters
static const struct AP_Param::GroupInfo var_info[];
private:
float _ki;
float _ki_yaw;