mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_AHRS_DCM: moved var_info to belong to AP_AHRS_DCM instead of AP_AHRS
This commit is contained in:
parent
ae119b08b3
commit
c2b47d2bf9
@ -30,7 +30,7 @@
|
|||||||
#define SPIN_RATE_LIMIT 20
|
#define SPIN_RATE_LIMIT 20
|
||||||
|
|
||||||
// table of user settable parameters
|
// table of user settable parameters
|
||||||
const AP_Param::GroupInfo AP_AHRS::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo AP_AHRS_DCM::var_info[] PROGMEM = {
|
||||||
// @Param: YAW_P
|
// @Param: YAW_P
|
||||||
// @DisplayName: Yaw P
|
// @DisplayName: Yaw P
|
||||||
// @Description: This controls the weight the compass has on the overall heading
|
// @Description: This controls the weight the compass has on the overall heading
|
||||||
|
@ -48,6 +48,9 @@ public:
|
|||||||
AP_Float _kp;
|
AP_Float _kp;
|
||||||
AP_Float gps_gain;
|
AP_Float gps_gain;
|
||||||
|
|
||||||
|
// for holding parameters
|
||||||
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
float _ki;
|
float _ki;
|
||||||
float _ki_yaw;
|
float _ki_yaw;
|
||||||
|
Loading…
Reference in New Issue
Block a user