Skip to content

Commit

Permalink
Make high rate IMU DcmKp change relative to user value (#13304)
Browse files Browse the repository at this point in the history
* make all IMU changes relative to user value

* comment above line
  • Loading branch information
ctzsnooze committed Jan 16, 2024
1 parent d039124 commit 926ef34
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions src/main/flight/imu.c
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,6 @@ static bool imuUpdated = false;

#define ATTITUDE_RESET_QUIET_TIME 250000 // 250ms - gyro quiet period after disarm before attitude reset
#define ATTITUDE_RESET_GYRO_LIMIT 15 // 15 deg/sec - gyro limit for quiet period
#define ATTITUDE_RESET_KP_GAIN 25.0 // dcmKpGain value to use during attitude reset
#define ATTITUDE_RESET_ACTIVE_TIME 500000 // 500ms - Time to wait for attitude to converge at high gain
#define GPS_COG_MIN_GROUNDSPEED 100 // 1.0m/s - the minimum groundspeed for a gps based IMU heading to be considered valid
// Better to have some update than none for GPS Rescue at slow return speeds
Expand Down Expand Up @@ -175,6 +174,7 @@ static float calculateThrottleAngleScale(uint16_t throttle_correction_angle)

void imuConfigure(uint16_t throttle_correction_angle, uint8_t throttle_correction_value)
{
// current default for imu_dcm_kp is 2500; our 'normal' or baseline value for imuDcmKp is 0.25
imuRuntimeConfig.imuDcmKp = imuConfig()->imu_dcm_kp / 10000.0f;
imuRuntimeConfig.imuDcmKi = imuConfig()->imu_dcm_ki / 10000.0f;
// magnetic declination has negative sign (positive clockwise when seen from top)
Expand Down Expand Up @@ -456,16 +456,16 @@ static float imuCalcKpGain(timeUs_t currentTimeUs, bool useAcc, float *gyroAvera
stateTimeout = currentTimeUs + ATTITUDE_RESET_ACTIVE_TIME;
arState = stReset;
}
// low gain during quiet phase
// low gain (value of 0.25 with defaults) during quiet phase
return imuRuntimeConfig.imuDcmKp;
case stReset:
if (cmpTimeUs(currentTimeUs, stateTimeout) >= 0) {
arState = stDisarmed;
}
// high gain after quiet period
return ATTITUDE_RESET_KP_GAIN;
// high gain, 100x greater than normal, or 25, after quiet period
return imuRuntimeConfig.imuDcmKp * 100.0f;
case stDisarmed:
// Scale the kP to generally converge faster when disarmed.
// Scale the kP to converge 10x faster when disarmed, ie 2.5
return imuRuntimeConfig.imuDcmKp * 10.0f;
}
} else {
Expand Down

0 comments on commit 926ef34

Please sign in to comment.