mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 01:35:41 +03:00
spacing
This commit is contained in:
parent
aa253a387d
commit
cabf7eaac3
7 changed files with 25 additions and 26 deletions
16
src/mw.c
16
src/mw.c
|
@ -51,11 +51,11 @@ uint16_t GPS_ground_course = 0; // degrees * 10
|
|||
int16_t nav[2];
|
||||
int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother
|
||||
int8_t nav_mode = NAV_MODE_NONE; // Navigation mode
|
||||
uint8_t GPS_numCh; // Number of channels
|
||||
uint8_t GPS_svinfo_chn[16]; // Channel number
|
||||
uint8_t GPS_svinfo_svid[16]; // Satellite ID
|
||||
uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
|
||||
uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
||||
uint8_t GPS_numCh; // Number of channels
|
||||
uint8_t GPS_svinfo_chn[16]; // Channel number
|
||||
uint8_t GPS_svinfo_svid[16]; // Satellite ID
|
||||
uint8_t GPS_svinfo_quality[16]; // Bitfield Qualtity
|
||||
uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Strength)
|
||||
|
||||
// Automatic ACC Offset Calibration
|
||||
uint16_t InflightcalibratingA = 0;
|
||||
|
@ -103,7 +103,7 @@ void annexCode(void)
|
|||
prop2 = 100;
|
||||
} else {
|
||||
if (rcData[THROTTLE] < 2000) {
|
||||
prop2 = 100 - (uint16_t) cfg.dynThrPID * (rcData[THROTTLE] - cfg.tpaBreakPoint) / (2000 - cfg.tpaBreakPoint);
|
||||
prop2 = 100 - (uint16_t)cfg.dynThrPID * (rcData[THROTTLE] - cfg.tpaBreakPoint) / (2000 - cfg.tpaBreakPoint);
|
||||
} else {
|
||||
prop2 = 100 - cfg.dynThrPID;
|
||||
}
|
||||
|
@ -143,7 +143,7 @@ void annexCode(void)
|
|||
}
|
||||
|
||||
tmp = constrain(rcData[THROTTLE], mcfg.mincheck, 2000);
|
||||
tmp = (uint32_t) (tmp - mcfg.mincheck) * 1000 / (2000 - mcfg.mincheck); // [MINCHECK;2000] -> [0;1000]
|
||||
tmp = (uint32_t)(tmp - mcfg.mincheck) * 1000 / (2000 - mcfg.mincheck); // [MINCHECK;2000] -> [0;1000]
|
||||
tmp2 = tmp / 100;
|
||||
rcCommand[THROTTLE] = lookupThrottleRC[tmp2] + (tmp - tmp2 * 100) * (lookupThrottleRC[tmp2 + 1] - lookupThrottleRC[tmp2]) / 100; // [0;1000] -> expo -> [MINTHROTTLE;MAXTHROTTLE]
|
||||
|
||||
|
@ -363,7 +363,7 @@ static void pidRewrite(void)
|
|||
// ----------PID controller----------
|
||||
for (axis = 0; axis < 3; axis++) {
|
||||
// -----Get the desired angle rate depending on flight mode
|
||||
if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2 ) { // MODE relying on ACC
|
||||
if ((f.ANGLE_MODE || f.HORIZON_MODE) && axis < 2) { // MODE relying on ACC
|
||||
// calculate error and limit the angle to max configured inclination
|
||||
errorAngle = constrain((rcCommand[axis] << 1) + GPS_angle[axis], -((int)mcfg.max_angle_inclination), +mcfg.max_angle_inclination) - angle[axis] + cfg.angleTrim[axis]; // 16 bits is ok here
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue