1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-26 09:45:37 +03:00

Add magnetic heading as debug and magnetic declination for the Mahony filter (#13073)

* Add mag heading to GPS Rescue heading debug

* Roll and pitch compensated magnetic yaw

* Changes according to PR comments

* Encapsulate yawMag calculations

* Corrected naming

* Changes according to PR comments

* Changes so that Checks don't fail

* Added PARAM_NAME list

* Changes so that Checks don't fail

* Changes according to PR comments

* Update src/main/fc/parameter_names.h

Co-authored-by: Mark Haslinghuis <mark@numloq.nl>

* Changes according to PR comments

* 200Hz compass task

* fix wait status flag

* increase default ODR of HMC5883L to 75Hz

* fix spikes in MagYaw debug by re-calc only on new data

---------

Co-authored-by: ctzsnooze <chris.thompson@sydney.edu.au>
Co-authored-by: Mark Haslinghuis <mark@numloq.nl>
This commit is contained in:
pichim 2023-09-27 00:01:22 +01:00 committed by GitHub
parent 1856d6f7ef
commit 9ada5638a3
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
10 changed files with 96 additions and 32 deletions

View file

@ -1003,16 +1003,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
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_kp) },
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_ki) },
{ "small_angle", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, small_angle) },
{ "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, 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) },