AP_Param: update AHRS for new constructor syntax
This commit is contained in:
parent
5e8fe8d93e
commit
898a5af692
@ -36,21 +36,21 @@ const AP_Param::GroupInfo AP_AHRS_DCM::var_info[] PROGMEM = {
|
||||
// @Description: This controls the weight the compass has on the overall heading
|
||||
// @Range: 0 .4
|
||||
// @Increment: .01
|
||||
AP_GROUPINFO("YAW_P", 0, AP_AHRS_DCM, _kp_yaw),
|
||||
AP_GROUPINFO("YAW_P", 0, 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", 1, AP_AHRS_DCM, _kp),
|
||||
AP_GROUPINFO("RP_P", 1, AP_AHRS_DCM, _kp, 0.4),
|
||||
|
||||
// @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),
|
||||
AP_GROUPINFO("GPS_GAIN", 2, AP_AHRS_DCM, gps_gain, 1.0),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -22,10 +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
|
||||
|
@ -34,14 +34,14 @@ const AP_Param::GroupInfo AP_AHRS_MPU6000::var_info[] PROGMEM = {
|
||||
// @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),
|
||||
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),
|
||||
AP_GROUPINFO("RP_P", 1, AP_AHRS_MPU6000, _kp, 0.4),
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -29,9 +29,6 @@ public:
|
||||
_ki = 0.0087;
|
||||
_ki_yaw = 0.01;
|
||||
|
||||
_kp.set(0.4);
|
||||
_kp_yaw.set(0.4);
|
||||
|
||||
// dmp related variable initialisation
|
||||
_gyro_bias_from_gravity_gain = 0.008;
|
||||
_compass_bias_time = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user