4 Commits

Author SHA1 Message Date
Oleg Kalachev
a8c25d8ac0 Minor updates to usage article 2026-02-04 17:52:23 +03:00
Oleg Kalachev
3e49d41986 Make rc channel numbers and calibration params use int instead of float
As parameter subsystems supports int now, and int is much more natural here.
2026-02-02 20:36:22 +03:00
Oleg Kalachev
67430c7aac Several minor changes 2026-02-02 18:46:36 +03:00
Oleg Kalachev
3631743a29 Drop messages from another systems in pyflix
We shouldn't pass messages where system id != our system id. 
This change may be useful when there are many drones in one network.
2026-02-02 18:28:20 +03:00
8 changed files with 43 additions and 40 deletions

View File

@@ -148,27 +148,29 @@ Reboot the drone to apply the changes.
> [!CAUTION]
> **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them.
### Check everything works
### Important: check everything works
1. Check the IMU is working: perform `imu` command and check its output:
1. Check the IMU is working: perform `imu` command in the console and check the output:
* The `status` field should be `OK`.
* The `rate` field should be about 1000 (Hz).
* The `accel` and `gyro` fields should change as you move the drone.
* The `accel bias` and `accel scale` fields should contain calibration parameters (not zeros and ones).
* The `gyro bias` field should contain estimated gyro bias (not zeros).
* The `landed` field should be `1` when the drone is still on the ground and `0` when you lift it up.
2. Check the attitude estimation: connect to the drone using QGroundControl, rotate the drone in different orientations and check if the attitude estimation shown in QGroundControl is correct. Compare your attitude indicator (in the *large vertical* mode) to the video:
<a href="https://youtu.be/yVRN23-GISU"><img width=300 src="https://i3.ytimg.com/vi/yVRN23-GISU/maxresdefault.jpg"></a>
3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!**
3. Perform motor tests. Use the following commands **— remove the propellers before running the tests!**
* `mfr` — should rotate front right motor (counter-clockwise).
* `mfl` — should rotate front left motor (clockwise).
* `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — should rotate rear right motor (clockwise).
* `mfr` — rotate front right motor (counter-clockwise).
* `mfl` — rotate front left motor (clockwise).
* `mrl` — rotate rear left motor (counter-clockwise).
* `mrr` — rotate rear right motor (clockwise).
Rotation diagram:
Make sure rotation directions and propeller types match the following diagram:
<img src="img/motors.svg" width=200>
@@ -234,11 +236,11 @@ When finished flying, **disarm** the drone, moving the left stick to the bottom
### Flight modes
Flight mode is changed using mode switch on the remote control or using the command line.
Flight mode is changed using mode switch on the remote control (if configured) or using the console commands. The main flight mode is *STAB*.
#### STAB
The default mode is *STAB*. In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles.
In this mode, the drone stabilizes its attitude (orientation). The left stick controls throttle and yaw rate, the right stick controls pitch and roll angles.
> [!IMPORTANT]
> The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually.
@@ -253,7 +255,7 @@ In this mode, the pilot controls the angular rates. This control method is diffi
#### AUTO
In this mode, the pilot inputs are ignored (except the mode switch, if configured). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed autonomous behavior.
In this mode, the pilot inputs are ignored (except the mode switch). The drone can be controlled using [pyflix](../tools/pyflix/) Python library, or by modifying the firmware to implement the needed behavior.
If the pilot moves the control sticks, the drone will switch back to *STAB* mode.

View File

@@ -1,7 +1,7 @@
// Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix
// Attitude estimation from gyro and accelerometer
// Attitude estimation using gyro and accelerometer
#include "quaternion.h"
#include "vector.h"

View File

@@ -21,8 +21,8 @@ void setup() {
disableBrownOut();
setupParameters();
setupLED();
setupMotors();
setLED(true);
setupMotors();
setupWiFi();
setupIMU();
setupRC();

View File

@@ -8,12 +8,13 @@
extern float controlTime;
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
int mavlinkSysId = 1;
Rate telemetryFast(10);
Rate telemetrySlow(2);
bool mavlinkConnected = false;
String mavlinkPrintBuffer;
void processMavlink() {
sendMavlink();
receiveMavlink();
@@ -41,9 +42,9 @@ void sendMavlink() {
}
if (telemetryFast && mavlinkConnected) {
const float zeroQuat[] = {0, 0, 0, 0};
const float offset[] = {0, 0, 0, 0};
mavlink_msg_attitude_quaternion_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg,
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, zeroQuat); // convert to frd
time, attitude.w, attitude.x, -attitude.y, -attitude.z, rates.x, -rates.y, -rates.z, offset); // convert to frd
sendMessage(&msg);
mavlink_msg_rc_channels_raw_pack(mavlinkSysId, MAV_COMP_ID_AUTOPILOT1, &msg, controlTime * 1000, 0,

View File

@@ -6,18 +6,18 @@
#include <Preferences.h>
#include "util.h"
extern float channelZero[16];
extern float channelMax[16];
extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int channelZero[16];
extern int channelMax[16];
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int wifiMode, udpLocalPort, udpRemotePort;
extern float rcLossTimeout, descendTime;
Preferences storage;
struct Parameter {
const char *name; // max length is 15 (Preferences key limit)
const char *name; // max length is 15
bool integer;
union { float *f; int *i; }; // pointer to variable
union { float *f; int *i; }; // pointer to the variable
float cache; // what's stored in flash
Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
@@ -112,6 +112,7 @@ Parameter parameters[] = {
};
void setupParameters() {
print("Setup parameters\n");
storage.begin("flix", false);
// Read parameters from storage
for (auto &parameter : parameters) {

View File

@@ -9,15 +9,14 @@
SBUS rc(Serial2);
uint16_t channels[16]; // raw rc channels
float channelZero[16]; // calibration zero values
float channelMax[16]; // calibration max values
int channelZero[16]; // calibration zero values
int channelMax[16]; // calibration max values
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN;
float controlTime = NAN; // time of the last controls update
// Channels mapping (nan means not assigned):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
int rollChannel = -1, pitchChannel = -1, throttleChannel = -1, yawChannel = -1, modeChannel = -1; // channel mapping
void setupRC() {
print("Setup RC\n");
@@ -41,11 +40,11 @@ void normalizeRC() {
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
}
// Update control values
controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : 0;
controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : 0;
controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : 0;
controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : 0;
controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; // mode switch should not have affect if not set
controlRoll = rollChannel < 0 ? 0 : controls[rollChannel];
controlPitch = pitchChannel < 0 ? 0 : controls[pitchChannel];
controlYaw = yawChannel < 0 ? 0 : controls[yawChannel];
controlThrottle = throttleChannel < 0 ? 0 : controls[throttleChannel];
controlMode = modeChannel < 0 ? NAN : controls[modeChannel]; // mode control is ineffective if not mapped
}
void calibrateRC() {
@@ -64,7 +63,7 @@ void calibrateRC() {
printRCCalibration();
}
void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str) {
void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const char *str) {
print("%s", str);
pause(3);
for (int i = 0; i < 30; i++) readRC(); // try update 30 times max
@@ -85,15 +84,15 @@ void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const
channelZero[ch] = in[ch];
channelMax[ch] = out[ch];
} else {
*channel = NAN;
*channel = -1;
}
}
void printRCCalibration() {
print("Control Ch Zero Max\n");
print("Roll %-7g%-7g%-7g\n", rollChannel, rollChannel >= 0 ? channelZero[(int)rollChannel] : NAN, rollChannel >= 0 ? channelMax[(int)rollChannel] : NAN);
print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN);
print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN);
print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN);
print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN);
print("Roll %-7d%-7d%-7d\n", rollChannel, rollChannel < 0 ? 0 : channelZero[rollChannel], rollChannel < 0 ? 0 : channelMax[rollChannel]);
print("Pitch %-7d%-7d%-7d\n", pitchChannel, pitchChannel < 0 ? 0 : channelZero[pitchChannel], pitchChannel < 0 ? 0 : channelMax[pitchChannel]);
print("Yaw %-7d%-7d%-7d\n", yawChannel, yawChannel < 0 ? 0 : channelZero[yawChannel], yawChannel < 0 ? 0 : channelMax[yawChannel]);
print("Throttle %-7d%-7d%-7d\n", throttleChannel, throttleChannel < 0 ? 0 : channelZero[throttleChannel], throttleChannel < 0 ? 0 : channelMax[throttleChannel]);
print("Mode %-7d%-7d%-7d\n", modeChannel, modeChannel < 0 ? 0 : channelZero[modeChannel], modeChannel < 0 ? 0 : channelMax[modeChannel]);
}

View File

@@ -43,7 +43,7 @@ void doCommand(String str, bool echo);
void handleInput();
void normalizeRC();
void calibrateRC();
void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void calibrateRCChannel(int *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration();
void printLogHeader();
void printLogData();

View File

@@ -138,7 +138,7 @@ class Flix:
while True:
try:
msg: Optional[mavlink.MAVLink_message] = self.connection.recv_match(blocking=True)
if msg is None:
if msg is None or msg.get_srcSystem() != self.system_id:
continue
self._connected()
msg_dict = msg.to_dict()