mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 03:20:00 +03:00
fixed a fuckup with yaw_rate that was caused by more 8bit leftover garbage
fixed althold vel/constrain typo thx Marcin flight-tested this build on my shitcopter, CAREFUL flight testing may commence. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@428 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
891bce4e19
commit
800ce6bdf7
3 changed files with 3238 additions and 3181 deletions
6395
obj/baseflight.hex
6395
obj/baseflight.hex
File diff suppressed because it is too large
Load diff
|
@ -388,7 +388,7 @@ int getEstimatedAltitude(void)
|
|||
// apply Complimentary Filter to keep the calculated velocity based on baro velocity (i.e. near real velocity).
|
||||
// By using CF it's possible to correct the drift of integrated accZ (velocity) without loosing the phase, i.e without delay
|
||||
vel = vel * cfg.baro_cf_vel + baroVel * (1 - cfg.baro_cf_vel);
|
||||
constrain(vel, -1000, 1000); // limit max velocity to +/- 10m/s (36km/h)
|
||||
vel = constrain(vel, -1000, 1000); // limit max velocity to +/- 10m/s (36km/h)
|
||||
|
||||
// D
|
||||
vel_tmp = vel;
|
||||
|
|
14
src/mw.c
14
src/mw.c
|
@ -87,14 +87,17 @@ void blinkLED(uint8_t num, uint8_t wait, uint8_t repeat)
|
|||
void annexCode(void)
|
||||
{
|
||||
static uint32_t calibratedAccTime;
|
||||
uint16_t tmp, tmp2;
|
||||
int32_t tmp, tmp2;
|
||||
int32_t axis, prop1, prop2;
|
||||
static uint8_t buzzerFreq; // delay between buzzer ring
|
||||
|
||||
// vbat shit
|
||||
static uint8_t vbatTimer = 0;
|
||||
uint8_t axis, prop1, prop2;
|
||||
static uint8_t ind = 0;
|
||||
uint16_t vbatRaw = 0;
|
||||
static uint16_t vbatRawArray[8];
|
||||
uint8_t i;
|
||||
|
||||
int i;
|
||||
|
||||
// PITCH & ROLL only dynamic PID adjustemnt, depending on throttle value
|
||||
if (rcData[THROTTLE] < BREAKPOINT) {
|
||||
|
@ -123,7 +126,6 @@ void annexCode(void)
|
|||
prop1 = 100 - (uint16_t) cfg.rollPitchRate * tmp / 500;
|
||||
prop1 = (uint16_t) prop1 *prop2 / 100;
|
||||
} else { // YAW
|
||||
tmp *= -mcfg.yaw_control_direction; //change control direction for yaw needed with new gyro orientation
|
||||
if (cfg.yawdeadband) {
|
||||
if (tmp > cfg.yawdeadband) {
|
||||
tmp -= cfg.yawdeadband;
|
||||
|
@ -131,8 +133,8 @@ void annexCode(void)
|
|||
tmp = 0;
|
||||
}
|
||||
}
|
||||
rcCommand[axis] = tmp;
|
||||
prop1 = 100 - (uint16_t) cfg.yawRate * tmp / 500;
|
||||
rcCommand[axis] = tmp * -mcfg.yaw_control_direction;
|
||||
prop1 = 100 - (uint16_t)cfg.yawRate * abs(tmp) / 500;
|
||||
}
|
||||
dynP8[axis] = (uint16_t)cfg.P8[axis] * prop1 / 100;
|
||||
dynI8[axis] = (uint16_t)cfg.I8[axis] * prop1 / 100;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue