mirror of
https://github.com/okalachev/flix.git
synced 2025-07-27 17:49:33 +00:00
Make dt=0 on first step, simplify code
This commit is contained in:
parent
4160b8da07
commit
9a93367629
@ -13,50 +13,36 @@
|
|||||||
|
|
||||||
void estimate()
|
void estimate()
|
||||||
{
|
{
|
||||||
if (dt == 0) {
|
applyGyro();
|
||||||
return;
|
applyAcc();
|
||||||
}
|
signalizeHorizontality();
|
||||||
|
}
|
||||||
|
|
||||||
|
void applyGyro()
|
||||||
|
{
|
||||||
// applying gyro
|
// applying gyro
|
||||||
attitude *= Quaternion::fromAngularRates(rates * dt);
|
attitude *= Quaternion::fromAngularRates(rates * dt);
|
||||||
attitude.normalize();
|
attitude.normalize();
|
||||||
|
}
|
||||||
|
|
||||||
// test should we apply acc
|
void applyAcc()
|
||||||
|
{
|
||||||
|
// test should we apply accelerometer gravity correction
|
||||||
float accNorm = acc.norm();
|
float accNorm = acc.norm();
|
||||||
if (accNorm < ACC_MIN * ONE_G || accNorm > ACC_MAX * ONE_G) {
|
if (accNorm < ACC_MIN * ONE_G || accNorm > ACC_MAX * ONE_G) {
|
||||||
// use acc only when we're not accelerating
|
// use accelerometer only when we're not accelerating
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// calculate accelerometer correction
|
||||||
Vector up = attitude.rotate(Vector(0, 0, -1));
|
Vector up = attitude.rotate(Vector(0, 0, -1));
|
||||||
Vector accCorrDirection = Vector::angularRatesBetweenVectors(acc, up);
|
Vector accCorrDirection = Vector::angularRatesBetweenVectors(acc, up);
|
||||||
accCorrDirection.normalize();
|
accCorrDirection.normalize();
|
||||||
|
|
||||||
if (!accCorrDirection.finite()) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
Vector accCorr = accCorrDirection * Vector::angleBetweenVectors(up, acc) * dt * WEIGHT_ACC;
|
Vector accCorr = accCorrDirection * Vector::angleBetweenVectors(up, acc) * dt * WEIGHT_ACC;
|
||||||
|
|
||||||
if (!accCorr.finite()) {
|
// apply correction
|
||||||
return; // TODO
|
|
||||||
}
|
|
||||||
|
|
||||||
attitude *= Quaternion::fromAngularRates(accCorr);
|
attitude *= Quaternion::fromAngularRates(accCorr);
|
||||||
attitude.normalize();
|
attitude.normalize();
|
||||||
|
|
||||||
if (!attitude.finite()) {
|
|
||||||
Serial.print("dt "); Serial.println(dt, 15);
|
|
||||||
Serial.print("up "); Serial.println(up);
|
|
||||||
Serial.print("acc "); Serial.println(acc);
|
|
||||||
Serial.print("acc norm "); Serial.println(acc.norm());
|
|
||||||
Serial.print("upp norm "); Serial.println(up.norm());
|
|
||||||
Serial.print("acc dot up "); Serial.println(Vector::dot(up, acc), 15);
|
|
||||||
Serial.print("acc cor ang "); Serial.println(Vector::angleBetweenVectors(up, acc), 15);
|
|
||||||
Serial.print("acc corr dir "); Serial.println(accCorrDirection);
|
|
||||||
Serial.print("acc cor "); Serial.println(accCorr);
|
|
||||||
Serial.print("att "); Serial.println(attitude);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void signalizeHorizontality()
|
void signalizeHorizontality()
|
||||||
|
@ -62,5 +62,4 @@ void loop()
|
|||||||
sendMavlink();
|
sendMavlink();
|
||||||
#endif
|
#endif
|
||||||
logData();
|
logData();
|
||||||
signalizeHorizontality();
|
|
||||||
}
|
}
|
||||||
|
11
flix/pid.h
11
flix/pid.h
@ -20,21 +20,12 @@ public:
|
|||||||
|
|
||||||
float update(float error, float dt)
|
float update(float error, float dt)
|
||||||
{
|
{
|
||||||
if (!isfinite(error) || !isfinite(dt)) {
|
|
||||||
// TODO: brutal way to remove glitches
|
|
||||||
Serial.println("nan in error or dt");
|
|
||||||
return NAN;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (dt > 0) {
|
|
||||||
// calculate integral if dt is valid
|
|
||||||
integral += error * dt;
|
integral += error * dt;
|
||||||
if (isfinite(prevError)) {
|
if (isfinite(prevError) && dt > 0) {
|
||||||
// calculate derivative if both dt and prevError are valid
|
// calculate derivative if both dt and prevError are valid
|
||||||
float _derivative = (error - prevError) / dt;
|
float _derivative = (error - prevError) / dt;
|
||||||
derivative = derivative * 0.8 + 0.2 * _derivative; // lpf WARNING:
|
derivative = derivative * 0.8 + 0.2 * _derivative; // lpf WARNING:
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
prevError = error;
|
prevError = error;
|
||||||
|
|
||||||
|
@ -1,14 +1,16 @@
|
|||||||
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
|
||||||
// Repository: https://github.com/okalachev/flix
|
// Repository: https://github.com/okalachev/flix
|
||||||
|
|
||||||
#define FREQ_WINDOW 1
|
|
||||||
|
|
||||||
void step()
|
void step()
|
||||||
{
|
{
|
||||||
float now = micros() / 1000000.0;
|
float now = micros() / 1000000.0;
|
||||||
dt = now - t; // dt is NAN on first step
|
dt = now - t;
|
||||||
t = now;
|
t = now;
|
||||||
|
|
||||||
|
if (isnan(dt)) {
|
||||||
|
dt = 0; // assume dt to be zero on first step
|
||||||
|
}
|
||||||
|
|
||||||
computeLoopFreq();
|
computeLoopFreq();
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -17,7 +19,7 @@ void computeLoopFreq()
|
|||||||
static float windowStart = 0;
|
static float windowStart = 0;
|
||||||
static uint32_t freq = 0;
|
static uint32_t freq = 0;
|
||||||
freq++;
|
freq++;
|
||||||
if (t - windowStart >= FREQ_WINDOW) {
|
if (t - windowStart >= 1) { // 1 second window
|
||||||
loopFreq = freq;
|
loopFreq = freq;
|
||||||
windowStart = t;
|
windowStart = t;
|
||||||
freq = 0;
|
freq = 0;
|
||||||
|
@ -13,10 +13,6 @@
|
|||||||
#include <unistd.h>
|
#include <unistd.h>
|
||||||
#include <sys/poll.h>
|
#include <sys/poll.h>
|
||||||
|
|
||||||
using std::max;
|
|
||||||
using std::min;
|
|
||||||
using std::isfinite;
|
|
||||||
|
|
||||||
#define PI 3.1415926535897932384626433832795
|
#define PI 3.1415926535897932384626433832795
|
||||||
#define DEG_TO_RAD 0.017453292519943295769236907684886
|
#define DEG_TO_RAD 0.017453292519943295769236907684886
|
||||||
#define RAD_TO_DEG 57.295779513082320876798154814105
|
#define RAD_TO_DEG 57.295779513082320876798154814105
|
||||||
|
@ -7,6 +7,7 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include "vector.h"
|
#include "vector.h"
|
||||||
#include "quaternion.h"
|
#include "quaternion.h"
|
||||||
|
#include "Arduino.h"
|
||||||
|
|
||||||
#define RC_CHANNELS 6
|
#define RC_CHANNELS 6
|
||||||
|
|
||||||
@ -15,7 +16,7 @@
|
|||||||
#define MOTOR_FRONT_RIGHT 2
|
#define MOTOR_FRONT_RIGHT 2
|
||||||
#define MOTOR_REAR_RIGHT 1
|
#define MOTOR_REAR_RIGHT 1
|
||||||
|
|
||||||
float t;
|
float t = NAN;
|
||||||
float dt;
|
float dt;
|
||||||
float loopFreq;
|
float loopFreq;
|
||||||
float motors[4];
|
float motors[4];
|
||||||
@ -27,6 +28,9 @@ Quaternion attitude;
|
|||||||
|
|
||||||
// declarations
|
// declarations
|
||||||
void computeLoopFreq();
|
void computeLoopFreq();
|
||||||
|
void applyGyro();
|
||||||
|
void applyAcc();
|
||||||
|
void signalizeHorizontality();
|
||||||
void control();
|
void control();
|
||||||
void interpretRC();
|
void interpretRC();
|
||||||
static void controlAttitude();
|
static void controlAttitude();
|
||||||
|
Loading…
x
Reference in New Issue
Block a user