mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 14:55:21 +03:00
Remove unused IMU parameters
This commit is contained in:
parent
649eaea291
commit
0074f05573
3 changed files with 1 additions and 16 deletions
|
@ -111,14 +111,12 @@ quaternion offset = QUATERNION_INITIALIZE;
|
||||||
// absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
// absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
||||||
attitudeEulerAngles_t attitude = EULER_INITIALIZE;
|
attitudeEulerAngles_t attitude = EULER_INITIALIZE;
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 1);
|
||||||
|
|
||||||
PG_RESET_TEMPLATE(imuConfig_t, imuConfig,
|
PG_RESET_TEMPLATE(imuConfig_t, imuConfig,
|
||||||
.dcm_kp = 2500, // 1.0 * 10000
|
.dcm_kp = 2500, // 1.0 * 10000
|
||||||
.dcm_ki = 0, // 0.003 * 10000
|
.dcm_ki = 0, // 0.003 * 10000
|
||||||
.small_angle = 25,
|
.small_angle = 25,
|
||||||
.accDeadband = {.xy = 40, .z= 40},
|
|
||||||
.acc_unarmedcal = 1
|
|
||||||
);
|
);
|
||||||
|
|
||||||
STATIC_UNIT_TESTED void imuComputeRotationMatrix(void){
|
STATIC_UNIT_TESTED void imuComputeRotationMatrix(void){
|
||||||
|
@ -159,7 +157,6 @@ void imuConfigure(uint16_t throttle_correction_angle, uint8_t throttle_correctio
|
||||||
{
|
{
|
||||||
imuRuntimeConfig.dcm_kp = imuConfig()->dcm_kp / 10000.0f;
|
imuRuntimeConfig.dcm_kp = imuConfig()->dcm_kp / 10000.0f;
|
||||||
imuRuntimeConfig.dcm_ki = imuConfig()->dcm_ki / 10000.0f;
|
imuRuntimeConfig.dcm_ki = imuConfig()->dcm_ki / 10000.0f;
|
||||||
imuRuntimeConfig.acc_unarmedcal = imuConfig()->acc_unarmedcal;
|
|
||||||
imuRuntimeConfig.small_angle = imuConfig()->small_angle;
|
imuRuntimeConfig.small_angle = imuConfig()->small_angle;
|
||||||
|
|
||||||
fc_acc = calculateAccZLowPassFilterRCTimeConstant(5.0f); // Set to fix value
|
fc_acc = calculateAccZLowPassFilterRCTimeConstant(5.0f); // Set to fix value
|
||||||
|
|
|
@ -56,17 +56,10 @@ typedef union {
|
||||||
|
|
||||||
extern attitudeEulerAngles_t attitude;
|
extern attitudeEulerAngles_t attitude;
|
||||||
|
|
||||||
typedef struct accDeadband_s {
|
|
||||||
uint8_t xy; // set the acc deadband for xy-Axis
|
|
||||||
uint8_t z; // set the acc deadband for z-Axis, this ignores small accelerations
|
|
||||||
} accDeadband_t;
|
|
||||||
|
|
||||||
typedef struct imuConfig_s {
|
typedef struct imuConfig_s {
|
||||||
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
|
uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
|
||||||
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
|
uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
|
||||||
uint8_t small_angle;
|
uint8_t small_angle;
|
||||||
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
|
|
||||||
accDeadband_t accDeadband;
|
|
||||||
} imuConfig_t;
|
} imuConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(imuConfig_t, imuConfig);
|
PG_DECLARE(imuConfig_t, imuConfig);
|
||||||
|
@ -74,9 +67,7 @@ PG_DECLARE(imuConfig_t, imuConfig);
|
||||||
typedef struct imuRuntimeConfig_s {
|
typedef struct imuRuntimeConfig_s {
|
||||||
float dcm_ki;
|
float dcm_ki;
|
||||||
float dcm_kp;
|
float dcm_kp;
|
||||||
uint8_t acc_unarmedcal;
|
|
||||||
uint8_t small_angle;
|
uint8_t small_angle;
|
||||||
accDeadband_t accDeadband;
|
|
||||||
} imuRuntimeConfig_t;
|
} imuRuntimeConfig_t;
|
||||||
|
|
||||||
void imuConfigure(uint16_t throttle_correction_angle, uint8_t throttle_correction_value);
|
void imuConfigure(uint16_t throttle_correction_angle, uint8_t throttle_correction_value);
|
||||||
|
|
|
@ -763,9 +763,6 @@ const clivalue_t valueTable[] = {
|
||||||
{ "serial_update_rate_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 100, 2000 }, PG_SERIAL_CONFIG, offsetof(serialConfig_t, serial_update_rate_hz) },
|
{ "serial_update_rate_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 100, 2000 }, PG_SERIAL_CONFIG, offsetof(serialConfig_t, serial_update_rate_hz) },
|
||||||
|
|
||||||
// PG_IMU_CONFIG
|
// PG_IMU_CONFIG
|
||||||
{ "accxy_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_IMU_CONFIG, offsetof(imuConfig_t, accDeadband.xy) },
|
|
||||||
{ "accz_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_IMU_CONFIG, offsetof(imuConfig_t, accDeadband.z) },
|
|
||||||
{ "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_IMU_CONFIG, offsetof(imuConfig_t, acc_unarmedcal) },
|
|
||||||
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_kp) },
|
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_kp) },
|
||||||
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_ki) },
|
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_ki) },
|
||||||
{ "small_angle", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, small_angle) },
|
{ "small_angle", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, small_angle) },
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue