Skip to content

Commit

Permalink
Changes according to PR comments
Browse files Browse the repository at this point in the history
  • Loading branch information
pichim committed Sep 15, 2023
1 parent 7e6badb commit adc9e9a
Show file tree
Hide file tree
Showing 7 changed files with 17 additions and 18 deletions.
11 changes: 5 additions & 6 deletions src/main/cli/settings.c
Original file line number Diff line number Diff line change
Expand Up @@ -1004,19 +1004,18 @@ const clivalue_t valueTable[] = {
{ "serial_update_rate_hz", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 100, 2000 }, PG_SERIAL_CONFIG, offsetof(serialConfig_t, serial_update_rate_hz) },

// PG_IMU_CONFIG
{ PARAM_NAME_IMU_DCM_KP, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_dcm_kp) },
{ PARAM_NAME_IMU_DCM_KI, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_dcm_ki) },
{ PARAM_NAME_IMU_SMALL_ANGLE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_small_angle) },
{ PARAM_NAME_IMU_PROCESS_DENOM, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, 4 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_process_denom) },
{ PARAM_NAME_IMU_DCM_KP, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_dcm_kp) },
{ PARAM_NAME_IMU_DCM_KI, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_dcm_ki) },
{ PARAM_NAME_IMU_SMALL_ANGLE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, small_angle) },
{ PARAM_NAME_IMU_PROCESS_DENOM, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, 4 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_process_denom) },
#ifdef USE_MAG
{ PARAM_NAME_IMU_MAG_DECLINATION, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 3599 }, PG_IMU_CONFIG, offsetof(imuConfig_t, imu_mag_declination) },
{ PARAM_NAME_IMU_MAG_DECLINATION, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 3599 }, PG_IMU_CONFIG, offsetof(imuConfig_t, mag_declination) },
#endif

// PG_ARMING_CONFIG
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 60 }, PG_ARMING_CONFIG, offsetof(armingConfig_t, auto_disarm_delay) },
{ PARAM_NAME_GYRO_CAL_ON_FIRST_ARM, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ARMING_CONFIG, offsetof(armingConfig_t, gyro_cal_on_first_arm) },


// PG_GPS_CONFIG
#ifdef USE_GPS
{ PARAM_NAME_GPS_PROVIDER, VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, PG_GPS_CONFIG, offsetof(gpsConfig_t, provider) },
Expand Down
4 changes: 2 additions & 2 deletions src/main/fc/parameter_names.h
Original file line number Diff line number Diff line change
Expand Up @@ -200,8 +200,8 @@

#define PARAM_NAME_IMU_DCM_KP "imu_dcm_kp"
#define PARAM_NAME_IMU_DCM_KI "imu_dcm_ki"
#define PARAM_NAME_IMU_SMALL_ANGLE "imu_small_angle"
#define PARAM_NAME_IMU_SMALL_ANGLE "small_angle"
#define PARAM_NAME_IMU_PROCESS_DENOM "imu_process_denom"
#ifdef USE_MAG
#define PARAM_NAME_IMU_MAG_DECLINATION "imu_mag_declination"
#define PARAM_NAME_IMU_MAG_DECLINATION "mag_declination"
#endif
8 changes: 4 additions & 4 deletions src/main/flight/imu.c
Original file line number Diff line number Diff line change
Expand Up @@ -121,9 +121,9 @@ PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 3);
PG_RESET_TEMPLATE(imuConfig_t, imuConfig,
.imu_dcm_kp = 2500, // 1.0 * 10000
.imu_dcm_ki = 0, // 0.003 * 10000
.imu_small_angle = 25,
.small_angle = 25,
.imu_process_denom = 2,
.imu_mag_declination = 0
.mag_declination = 0
);

static void imuQuaternionComputeProducts(quaternion *quat, quaternionProducts *quatProd)
Expand Down Expand Up @@ -172,11 +172,11 @@ void imuConfigure(uint16_t throttle_correction_angle, uint8_t throttle_correctio
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)
const float imuMagneticDeclinationRad = DEGREES_TO_RADIANS(imuConfig()->imu_mag_declination / 10.0f);
const float imuMagneticDeclinationRad = DEGREES_TO_RADIANS(imuConfig()->mag_declination / 10.0f);
north_ef.x = cos_approx(imuMagneticDeclinationRad);
north_ef.y = -sin_approx(imuMagneticDeclinationRad);

smallAngleCosZ = cos_approx(degreesToRadians(imuConfig()->imu_small_angle));
smallAngleCosZ = cos_approx(degreesToRadians(imuConfig()->small_angle));

throttleAngleScale = calculateThrottleAngleScale(throttle_correction_angle);

Expand Down
4 changes: 2 additions & 2 deletions src/main/flight/imu.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,9 +55,9 @@ extern float rMat[3][3];
typedef struct imuConfig_s {
uint16_t imu_dcm_kp; // DCM filter proportional gain ( x 10000)
uint16_t imu_dcm_ki; // DCM filter integral gain ( x 10000)
uint8_t imu_small_angle;
uint8_t small_angle;
uint8_t imu_process_denom;
uint16_t imu_mag_declination; // Magnetic declination in degrees * 10
uint16_t mag_declination; // Magnetic declination in degrees * 10
} imuConfig_t;

PG_DECLARE(imuConfig_t, imuConfig);
Expand Down
4 changes: 2 additions & 2 deletions src/main/msp/msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -1367,7 +1367,7 @@ case MSP_NAME:
case MSP_ARMING_CONFIG:
sbufWriteU8(dst, armingConfig()->auto_disarm_delay);
sbufWriteU8(dst, 0);
sbufWriteU8(dst, imuConfig()->imu_small_angle);
sbufWriteU8(dst, imuConfig()->small_angle);
break;

case MSP_RC_TUNING:
Expand Down Expand Up @@ -2680,7 +2680,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP,
armingConfigMutable()->auto_disarm_delay = sbufReadU8(src);
sbufReadU8(src); // reserved
if (sbufBytesRemaining(src)) {
imuConfigMutable()->imu_small_angle = sbufReadU8(src);
imuConfigMutable()->small_angle = sbufReadU8(src);
}
break;

Expand Down
2 changes: 1 addition & 1 deletion src/main/osd/osd_elements.c
Original file line number Diff line number Diff line change
Expand Up @@ -836,7 +836,7 @@ static void osdElementCrashFlipArrow(osdElementParms_t *element)
rollAngle = (rollAngle < 0 ? -180 : 180) - rollAngle;
}

if ((isFlipOverAfterCrashActive() || (!ARMING_FLAG(ARMED) && !isUpright())) && !((imuConfig()->imu_small_angle < 180 && isUpright()) || (rollAngle == 0 && pitchAngle == 0))) {
if ((isFlipOverAfterCrashActive() || (!ARMING_FLAG(ARMED) && !isUpright())) && !((imuConfig()->small_angle < 180 && isUpright()) || (rollAngle == 0 && pitchAngle == 0))) {
if (abs(pitchAngle) < 2 * abs(rollAngle) && abs(rollAngle) < 2 * abs(pitchAngle)) {
if (pitchAngle > 0) {
if (rollAngle > 0) {
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/flight_imu_unittest.cc
Original file line number Diff line number Diff line change
Expand Up @@ -179,7 +179,7 @@ TEST(FlightImuTest, TestSmallAngle)
const float r2 = 0.438;

// given
imuConfigMutable()->imu_small_angle = 25;
imuConfigMutable()->small_angle = 25;
imuConfigure(0, 0);
attitudeIsEstablished = true;

Expand Down

0 comments on commit adc9e9a

Please sign in to comment.