mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 16:25:31 +03:00
reload GPS pids on each eeprom read
git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@389 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
f9b48925fa
commit
fa7eecac18
3 changed files with 5 additions and 4 deletions
|
@ -85,6 +85,7 @@ void readEEPROM(void)
|
|||
|
||||
cfg.tri_yaw_middle = constrain(cfg.tri_yaw_middle, cfg.tri_yaw_min, cfg.tri_yaw_max); //REAR
|
||||
setPIDController(cfg.pidController);
|
||||
GPS_set_pids();
|
||||
}
|
||||
|
||||
void writeEEPROM(uint8_t b, uint8_t updateProfile)
|
||||
|
|
|
@ -8,7 +8,6 @@
|
|||
const uint32_t init_speed[5] = { 9600, 19200, 38400, 57600, 115200 };
|
||||
|
||||
static void GPS_NewData(uint16_t c);
|
||||
static void GPS_set_pids(void);
|
||||
static void gpsPrint(const char *str);
|
||||
|
||||
static const char * const gpsInitStrings[] = {
|
||||
|
@ -407,7 +406,7 @@ void GPS_reset_nav(void)
|
|||
}
|
||||
|
||||
// Get the relevant P I D values and set the PID controllers
|
||||
static void GPS_set_pids(void)
|
||||
void GPS_set_pids(void)
|
||||
{
|
||||
posholdPID_PARAM.kP = (float)cfg.P8[PIDPOS] / 100.0f;
|
||||
posholdPID_PARAM.kI = (float)cfg.I8[PIDPOS] / 100.0f;
|
||||
|
|
1
src/mw.h
1
src/mw.h
|
@ -457,6 +457,7 @@ void cliProcess(void);
|
|||
void gpsInit(uint32_t baudrate);
|
||||
void GPS_reset_home_position(void);
|
||||
void GPS_reset_nav(void);
|
||||
void GPS_set_pids(void);
|
||||
void GPS_set_next_wp(int32_t* lat, int32_t* lon);
|
||||
int32_t wrap_18000(int32_t error);
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue