mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 21:35:44 +03:00
spacing
This commit is contained in:
parent
aa253a387d
commit
cabf7eaac3
7 changed files with 25 additions and 26 deletions
|
@ -359,7 +359,7 @@ int getEstimatedAltitude(void)
|
||||||
|
|
||||||
// Integrator - Altitude in cm
|
// Integrator - Altitude in cm
|
||||||
accAlt += (vel_acc * 0.5f) * dt + vel * dt; // integrate velocity to get distance (x= a/2 * t^2)
|
accAlt += (vel_acc * 0.5f) * dt + vel * dt; // integrate velocity to get distance (x= a/2 * t^2)
|
||||||
accAlt = accAlt * cfg.baro_cf_alt + (float) BaroAlt *(1.0f - cfg.baro_cf_alt); // complementary filter for Altitude estimation (baro & acc)
|
accAlt = accAlt * cfg.baro_cf_alt + (float)BaroAlt * (1.0f - cfg.baro_cf_alt); // complementary filter for Altitude estimation (baro & acc)
|
||||||
EstAlt = accAlt;
|
EstAlt = accAlt;
|
||||||
vel += vel_acc;
|
vel += vel_acc;
|
||||||
|
|
||||||
|
|
6
src/mw.c
6
src/mw.c
|
@ -103,7 +103,7 @@ void annexCode(void)
|
||||||
prop2 = 100;
|
prop2 = 100;
|
||||||
} else {
|
} else {
|
||||||
if (rcData[THROTTLE] < 2000) {
|
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 {
|
} else {
|
||||||
prop2 = 100 - cfg.dynThrPID;
|
prop2 = 100 - cfg.dynThrPID;
|
||||||
}
|
}
|
||||||
|
@ -143,7 +143,7 @@ void annexCode(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
tmp = constrain(rcData[THROTTLE], mcfg.mincheck, 2000);
|
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;
|
tmp2 = tmp / 100;
|
||||||
rcCommand[THROTTLE] = lookupThrottleRC[tmp2] + (tmp - tmp2 * 100) * (lookupThrottleRC[tmp2 + 1] - lookupThrottleRC[tmp2]) / 100; // [0;1000] -> expo -> [MINTHROTTLE;MAXTHROTTLE]
|
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----------
|
// ----------PID controller----------
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
// -----Get the desired angle rate depending on flight mode
|
// -----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
|
// 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
|
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
|
||||||
}
|
}
|
||||||
|
|
|
@ -20,7 +20,7 @@ static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
|
||||||
void sbusInit(rcReadRawDataPtr *callback)
|
void sbusInit(rcReadRawDataPtr *callback)
|
||||||
{
|
{
|
||||||
int b;
|
int b;
|
||||||
for (b = 0; b < SBUS_MAX_CHANNEL; b ++)
|
for (b = 0; b < SBUS_MAX_CHANNEL; b++)
|
||||||
sbusChannelData[b] = 2 * (mcfg.midrc - SBUS_OFFSET);
|
sbusChannelData[b] = 2 * (mcfg.midrc - SBUS_OFFSET);
|
||||||
core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS));
|
core.rcvrport = uartOpen(USART2, sbusDataReceive, 100000, (portMode_t)(MODE_RX | MODE_SBUS));
|
||||||
if (callback)
|
if (callback)
|
||||||
|
|
|
@ -264,7 +264,6 @@ void Baro_Common(void)
|
||||||
baroHistIdx = indexplus1;
|
baroHistIdx = indexplus1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
int Baro_update(void)
|
int Baro_update(void)
|
||||||
{
|
{
|
||||||
static uint32_t baroDeadline = 0;
|
static uint32_t baroDeadline = 0;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue