Skip to content

Instantly share code, notes, and snippets.

@okalachev
Last active February 29, 2024 19:34
Show Gist options
  • Save okalachev/1a78143896340c2bec212f153d996d62 to your computer and use it in GitHub Desktop.
Save okalachev/1a78143896340c2bec212f153d996d62 to your computer and use it in GitHub Desktop.
Code for making an automatic flip for Flix drone (draft) https://github.com/okalachev/flix. See the video at https://t.me/opensourcequadcopter/21
// Copyright (c) 2024 Oleg Kalachev <okalachev@gmail.com>
// Flip controller for the Flix drone https://github.com/okalachev/flix
// Video and details: https://t.me/opensourcequadcopter/21
#define BOUNCE_TIME 0.6
#define ACCELERATE_TIME 0.07
#define BRAKE_TIME ACCELERATE_TIME
enum {
WAIT,
BOUNCE,
ACCELERATE,
ROTATE,
BRAKE,
POST_BRAKE,
RECOVERY
} flipStage = ACCELERATE;
void controlFlip() {
if (!armed) {
memset(motors, 0, sizeof(motors));
return;
}
static float stageTime = 0;
static float lastTime = -999;
static float maxRate = 0;
static float accelerationAngleZ;
static float brakeTime;
static float accelerationWhenRotatingTime;
if (t - lastTime > 0.1) {
// flip reset
flipStage = WAIT;
stageTime = t;
maxRate = 0;
}
lastTime = t;
if (flipStage == WAIT) {
// wait for ideal conditions
controls[RC_CHANNEL_MODE] = 0; // stab mode
interpretRC();
if (abs(rates.x) < 0.05 && (abs(attitude.toEulerZYX().x) < 0.02)) {
flipStage = BOUNCE;
stageTime = t;
}
} else if (flipStage == BOUNCE) {
thrustTarget = 0.8;
attitudeTarget = Quaternion::fromEulerZYX(Vector(0, 0, attitude.getYaw()));
yawMode = YAW;
controlAttitude();
controlRate();
controlTorque();
if (t - stageTime > BOUNCE_TIME) {
flipStage = ACCELERATE;
stageTime = t;
}
} else if (flipStage == ACCELERATE) {
thrustTarget = 0.1; // mark for log analysis
motors[MOTOR_REAR_LEFT] = 1;
motors[MOTOR_REAR_RIGHT] = 0;
motors[MOTOR_FRONT_LEFT] = 1;
motors[MOTOR_FRONT_RIGHT] = 0;
if (t - stageTime > ACCELERATE_TIME) {
flipStage = ROTATE;
stageTime = t;
}
} else if (flipStage == ROTATE) {
thrustTarget = 0.2; // mark for log analysis
// free rotation
memset(motors, 0, sizeof(motors));
Vector up = attitude.rotate(Vector(0, 0, -1));
if (abs(rates.x) > abs(maxRate)) {
maxRate = rates.x;
accelerationAngleZ = up.z;
accelerationWhenRotatingTime = t - stageTime;
}
if (up.z < accelerationAngleZ) {
flipStage = BRAKE;
stageTime = t;
}
} else if (flipStage == BRAKE) {
thrustTarget = 0.3; // mark for log analysis
motors[MOTOR_REAR_LEFT] = 0;
motors[MOTOR_REAR_RIGHT] = 1;
motors[MOTOR_FRONT_LEFT] = 0;
motors[MOTOR_FRONT_RIGHT] = 1;
if (t - stageTime > BRAKE_TIME) {
flipStage = POST_BRAKE;
stageTime = t;
}
} else if (flipStage == POST_BRAKE) {
thrustTarget = 0.4; // mark for log analysis
motors[MOTOR_REAR_LEFT] = 0.3;
motors[MOTOR_REAR_RIGHT] = 0.3;
motors[MOTOR_FRONT_LEFT] = 0.3;
motors[MOTOR_FRONT_RIGHT] = 0.3;
if (t - stageTime > accelerationWhenRotatingTime) {
flipStage = RECOVERY;
stageTime = t;
rollRatePID.reset();
pitchRatePID.reset();
yawRatePID.reset();
}
} else if (flipStage == RECOVERY) {
controls[RC_CHANNEL_MODE] = 0; // stab mode
interpretRC();
if (t - stageTime < 0.4) {
// gain thrust on first 0.4 seconds
thrustTarget = 0.8;
}
}
}
diff --git a/flix/control.ino b/flix/control.ino
index ce0f0d6..b1c5ac8 100644
--- a/flix/control.ino
+++ b/flix/control.ino
@@ -74,7 +74,9 @@ void interpretRC() {
if (controls[RC_CHANNEL_MODE] < 0.25) {
mode = STAB;
} else if (controls[RC_CHANNEL_MODE] < 0.75) {
- mode = STAB;
+ mode = USER;
+ controlFlip();
+ return;
} else {
mode = STAB;
}
diff --git a/flix/imu.ino b/flix/imu.ino
index acbade5..026a1c6 100644
--- a/flix/imu.ino
+++ b/flix/imu.ino
@@ -25,6 +25,7 @@ void setupIMU() {
if (LOAD_GYRO_CAL) loadGyroCal();
loadAccelCal();
+ IMU.setGyroRange(MPU9250::GYRO_RANGE_2000DPS); // this somehow lowers IMU rate to 500 Hz despite the SRD setting
IMU.setSrd(0); // set sample rate to 1000 Hz
// NOTE: very important, without the above the rate would be terrible 50 Hz
}
diff --git a/gazebo/flix.h b/gazebo/flix.h
index a8ce214..cb9d062 100644
--- a/gazebo/flix.h
+++ b/gazebo/flix.h
@@ -48,6 +48,7 @@ void sendMavlink();
void sendMessage(const void *msg);
void receiveMavlink();
void handleMavlink(const void *_msg);
+void controlFlip();
// mocks
void setLED(bool on) {};
diff --git a/gazebo/simulator.cpp b/gazebo/simulator.cpp
index f681513..5b2a556 100644
--- a/gazebo/simulator.cpp
+++ b/gazebo/simulator.cpp
@@ -26,6 +26,7 @@
#include "log.ino"
#include "cli.ino"
#include "mavlink.ino"
+#include "flip.ino"
#include "lpf.h"
using ignition::math::Vector3d;
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment