mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
Avoid passing a uint8_t to a gyro method that is only used during gyro
calibration. Conflicts: src/config.c src/flight_imu.c src/mw.h src/sensors.c src/serial_cli.c
This commit is contained in:
parent
9d56b4a00f
commit
11863e5c34
7 changed files with 29 additions and 10 deletions
|
@ -163,7 +163,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "yaw_control_direction", VAR_INT8, &masterConfig.yaw_control_direction, -1, 1 },
|
||||
{ "acc_hardware", VAR_UINT8, &masterConfig.acc_hardware, 0, 5 },
|
||||
{ "max_angle_inclination", VAR_UINT16, &masterConfig.max_angle_inclination, 100, 900 },
|
||||
{ "moron_threshold", VAR_UINT8, &masterConfig.moron_threshold, 0, 128 },
|
||||
{ "moron_threshold", VAR_UINT8, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, 0, 128 },
|
||||
{ "gyro_lpf", VAR_UINT16, &masterConfig.gyro_lpf, 0, 256 },
|
||||
{ "gyro_cmpf_factor", VAR_UINT16, &masterConfig.gyro_cmpf_factor, 100, 1000 },
|
||||
{ "gyro_cmpfm_factor", VAR_UINT16, &masterConfig.gyro_cmpfm_factor, 100, 1000 },
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue