mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 09:16:07 +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
|
@ -7,11 +7,14 @@
|
|||
#include "common/axis.h"
|
||||
#include "flight_common.h"
|
||||
|
||||
#include "sensors_common.h"
|
||||
|
||||
|
||||
#include "drivers/accgyro_common.h"
|
||||
#include "drivers/system_common.h"
|
||||
|
||||
#include "sensors_common.h"
|
||||
#include "sensors_gyro.h"
|
||||
|
||||
#include "statusindicator.h"
|
||||
#include "sensors_acceleration.h"
|
||||
#include "sensors_barometer.h"
|
||||
|
@ -20,7 +23,6 @@
|
|||
|
||||
#include "drivers/serial_common.h"
|
||||
#include "flight_mixer.h"
|
||||
#include "sensors_common.h"
|
||||
#include "boardalignment.h"
|
||||
#include "battery.h"
|
||||
#include "gimbal.h"
|
||||
|
@ -87,6 +89,7 @@ void activateConfig(void)
|
|||
generatePitchCurve(¤tProfile.controlRateConfig);
|
||||
generateThrottleCurve(¤tProfile.controlRateConfig, masterConfig.minthrottle, masterConfig.maxthrottle);
|
||||
|
||||
useGyroConfig(&masterConfig.gyroConfig);
|
||||
setPIDController(currentProfile.pidController);
|
||||
gpsUseProfile(¤tProfile.gpsProfile);
|
||||
gpsUsePIDs(¤tProfile.pidProfile);
|
||||
|
@ -273,7 +276,7 @@ static void resetConf(void)
|
|||
masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
|
||||
masterConfig.max_angle_inclination = 500; // 50 degrees
|
||||
masterConfig.yaw_control_direction = 1;
|
||||
masterConfig.moron_threshold = 32;
|
||||
masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
|
||||
masterConfig.batteryConfig.vbatscale = 110;
|
||||
masterConfig.batteryConfig.vbatmaxcellvoltage = 43;
|
||||
masterConfig.batteryConfig.vbatmincellvoltage = 33;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue