13 Commits

Author SHA1 Message Date
Oleg Kalachev
c434107eaf Add parameter for configuring sbus pin number, disable sbus by default 2026-03-27 00:56:34 +03:00
Oleg Kalachev
814427dbfd Minor docs change 2026-03-27 00:40:19 +03:00
Oleg Kalachev
0730ceeffa Add new user builds 2026-02-21 07:12:36 +03:00
Oleg Kalachev
a687303062 Make motor parameters apply without reboot
Add callback to parameter definition to call after parameter is changed.
2026-02-19 04:56:12 +03:00
Oleg Kalachev
b2daf2587f Minor parameters code simplifications
readOnly is false by default
INFINITY == INFINITY, so remove redundant check
2026-02-19 02:59:38 +03:00
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
Oleg Kalachev
3dde380bb7 Add parameters for list of modes bound to rc switch
Parameters: CTL_FLT_MODE_0, CTL_FLT_MODE_1, CTL_FLT_MODE_2.
Also fix a bug with incorrect choosing the mode from controlMode.
2026-01-27 16:38:20 +03:00
Oleg Kalachev
377b21429b Fix error when launching the sim
Also make the parameters WIFI_LOC_PORT and WIFI_REM_PORT work in the sim.
2026-01-27 16:32:52 +03:00
Oleg Kalachev
1ac443d6f8 Add a build by Arky Matsekh 2026-01-27 15:17:58 +03:00
Oleg Kalachev
964c0f7bc1 Make setting parameter in console printing actual parameter value.
In some cases, it would not be equal to the requested value.
2026-01-27 09:28:01 +03:00
25 changed files with 124 additions and 73 deletions

Binary file not shown.

After

Width:  |  Height:  |  Size: 62 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 55 KiB

BIN
docs/img/user/phalko/1.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 105 KiB

BIN
docs/img/user/phalko/2.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 34 KiB

BIN
docs/img/user/phalko/3.jpg Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 36 KiB

View File

@@ -13,7 +13,7 @@ Do the following:
Do the following:
* **Check the battery voltage**. Use a multimeter to measure the battery voltage. It should be in range of 3.7-4.2 V.
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button to make sure you see the whole ESP32 startup output.
* **Check if there are some startup errors**. Connect the ESP32 to the computer and check the Serial Monitor output. Use the Reset button or `reboot` command to see the whole startup output.
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200.
* **Make sure correct IMU model is chosen**. If using ICM-20948/MPU-6050 board, change `MPU9250` to `ICM20948`/`MPU6050` in the `imu.ino` file.
* **Check if the console is working**. Perform `help` command in Serial Monitor. You should see the list of available commands. You can also access the console using QGroundControl *(Vehicle Setup**Analyze Tools**MAVLink Console)*.
@@ -35,5 +35,7 @@ Do the following:
* **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture:
<img src="img/user/peter_ukhov-2/1.jpg" width="200">
* **Check the remote control**. Using `rc` command, check the control values reflect your sticks movement. All the controls should change between -1 and 1, and throttle between 0 and 1.
* If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
* **If using SBUS receiver**:
* **Define the used GPIO pin** in `RC_RX_PIN` parameter.
* **Calibrate the RC** using `cr` command in the console.
* **Check the IMU output using QGroundControl**. Connect to the drone using QGroundControl on your computer. Go to the *Analyze* tab, *MAVLINK Inspector*. Plot the data from the `SCALED_IMU` message. The gyroscope and accelerometer data should change according to the drone movement.

View File

@@ -143,32 +143,32 @@ If using brushless motors and ESCs:
1. Set the appropriate PWM using the parameters: `MOT_PWM_STOP`, `MOT_PWM_MIN`, and `MOT_PWM_MAX` (1000, 1000, and 2000 is typical).
2. Decrease the PWM frequency using the `MOT_PWM_FREQ` parameter (400 is typical).
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>
@@ -193,11 +193,13 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
### Control with a remote control
Before using remote SBUS-connected remote control, you need to calibrate it:
Before using SBUS-connected remote control you need to enable SBUS and calibrate it:
1. Access the console using QGroundControl (recommended) or Serial Monitor.
2. Type `cr` command and follow the instructions.
3. Use the remote control to fly the drone!
1. Connect to the drone using QGroundControl.
2. In parameters, set the `RC_RX_PIN` parameter to the GPIO pin number where the SBUS signal is connected, for example: 4. Negative value disables SBUS.
3. Reboot the drone to apply changes.
4. Open the console, type `cr` command and follow the instructions to calibrate the remote control.
5. Use the remote control to fly the drone!
### Control with a USB remote control
@@ -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

@@ -4,6 +4,33 @@ This page contains user-built drones based on the Flix project. Publish your pro
---
Author: [FanBy0ru](https://https://github.com/FanBy0ru).<br>
Description: custom 3D-printed frame.<br>
Frame STLs and flight validation: https://cults3d.com/en/3d-model/gadget/armature-pour-flix-drone.
<img src="img/user/fanby0ru/1.jpg" height=200> <img src="img/user/fanby0ru/2.jpg" height=200>
---
Author: Ivan44 Phalko.<br>
Description: custom PCB, cusom test bench.<br>
[Flight validation](https://drive.google.com/file/d/17DNDJ1gPmCmDRAwjedCbJ9RXAyqMqqcX/view?usp=sharing).
<img src="img/user/phalko/1.jpg" height=200> <img src="img/user/phalko/2.jpg" height=200> <img src="img/user/phalko/3.jpg" height=200>
---
Author: **Arkadiy "Arky" Matsekh**, Foucault Dynamics, Gold Coast, Australia.<br>
The drone was built for the University of Queensland industry-led Master's capstone project.
**Flight video:**
<a href="https://drive.google.com/file/d/1NNYSVXBY-w0JjCo07D8-PgnVq3ca9plj/view?usp=sharing"><img height=300 src="img/user/arkymatsekh/video.jpg"></a>
<img src="img/user/arkymatsekh/1.jpg" height=150> <img src="img/user/arkymatsekh/2.jpg" height=150> <img src="img/user/arkymatsekh/3.jpg" height=150>
---
Author: [goldarte](https://t.me/goldarte).<br>
<img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>

View File

@@ -94,7 +94,7 @@ void doCommand(String str, bool echo = false) {
} else if (command == "p") {
bool success = setParameter(arg0.c_str(), arg1.toFloat());
if (success) {
print("%s = %g\n", arg0.c_str(), arg1.toFloat());
print("%s = %g\n", arg0.c_str(), getParameter(arg0.c_str()));
} else {
print("Parameter not found: %s\n", arg0.c_str());
}

View File

@@ -52,6 +52,7 @@ PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_MAX;
int flightModes[] = {STAB, STAB, STAB}; // map for rc mode switch
extern const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
@@ -65,9 +66,9 @@ void control() {
}
void interpretControls() {
if (controlMode < 0.25) mode = STAB;
if (controlMode < 0.75) mode = STAB;
if (controlMode > 0.75) mode = STAB;
if (controlMode < 0.25) mode = flightModes[0];
else if (controlMode < 0.75) mode = flightModes[1];
else if (controlMode > 0.75) mode = flightModes[2];
if (mode == AUTO) return; // pilot is not effective in AUTO 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

@@ -24,6 +24,7 @@ void setupMotors() {
// configure pins
for (int i = 0; i < 4; i++) {
ledcAttach(motorPins[i], pwmFrequency, pwmResolution);
pwmFrequency = ledcChangeFrequency(motorPins[i], pwmFrequency, pwmResolution); // when reconfiguring
}
sendMotors();
print("Motors initialized\n");

View File

@@ -6,21 +6,23 @@
#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 rcRxPin;
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) {};
void (*callback)(); // called after parameter change
Parameter(const char *name, float *variable, void (*callback)() = nullptr) : name(name), integer(false), f(variable), callback(callback) {};
Parameter(const char *name, int *variable, void (*callback)() = nullptr) : name(name), integer(true), i(variable), callback(callback) {};
float getValue() const { return integer ? *i : *f; };
void setValue(const float value) { if (integer) *i = value; else *f = value; };
};
@@ -49,6 +51,9 @@ Parameter parameters[] = {
{"CTL_R_RATE_MAX", &maxRate.x},
{"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax},
{"CTL_FLT_MODE_0", &flightModes[0]},
{"CTL_FLT_MODE_1", &flightModes[1]},
{"CTL_FLT_MODE_2", &flightModes[2]},
// imu
{"IMU_ROT_ROLL", &imuRotation.x},
{"IMU_ROT_PITCH", &imuRotation.y},
@@ -64,16 +69,17 @@ Parameter parameters[] = {
{"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha},
// motors
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT]},
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
{"MOT_PWM_FREQ", &pwmFrequency},
{"MOT_PWM_RES", &pwmResolution},
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT], setupMotors},
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT], setupMotors},
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT], setupMotors},
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT], setupMotors},
{"MOT_PWM_FREQ", &pwmFrequency, setupMotors},
{"MOT_PWM_RES", &pwmResolution, setupMotors},
{"MOT_PWM_STOP", &pwmStop},
{"MOT_PWM_MIN", &pwmMin},
{"MOT_PWM_MAX", &pwmMax},
// rc
{"RC_RX_PIN", &rcRxPin},
{"RC_ZERO_0", &channelZero[0]},
{"RC_ZERO_1", &channelZero[1]},
{"RC_ZERO_2", &channelZero[2]},
@@ -109,7 +115,8 @@ Parameter parameters[] = {
};
void setupParameters() {
storage.begin("flix", false);
print("Setup parameters\n");
storage.begin("flix");
// Read parameters from storage
for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) {
@@ -148,6 +155,7 @@ bool setParameter(const char *name, const float value) {
if (strcasecmp(parameter.name, name) == 0) {
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
parameter.setValue(value);
if (parameter.callback) parameter.callback();
return true;
}
}
@@ -161,8 +169,7 @@ void syncParameters() {
for (auto &parameter : parameters) {
if (parameter.getValue() == parameter.cache) continue; // no change
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NAN
storage.putFloat(parameter.name, parameter.getValue());
parameter.cache = parameter.getValue(); // update cache

View File

@@ -7,24 +7,26 @@
#include "util.h"
SBUS rc(Serial2);
int rcRxPin = -1; // -1 means disabled
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() {
if (rcRxPin < 0) return;
print("Setup RC\n");
rc.begin();
rc.begin(rcRxPin);
}
bool readRC() {
if (rcRxPin < 0) return false;
if (rc.read()) {
SBUSData data = rc.data();
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
@@ -41,14 +43,18 @@ 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() {
if (rcRxPin < 0) {
print("RC_RX_PIN = %d, set the RC pin!\n", rcRxPin);
return;
}
uint16_t zero[16];
uint16_t center[16];
uint16_t max[16];
@@ -64,7 +70,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 +91,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

@@ -165,6 +165,7 @@ void delay(uint32_t ms) {
bool ledcAttach(uint8_t pin, uint32_t freq, uint8_t resolution) { return true; }
bool ledcWrite(uint8_t pin, uint32_t duty) { return true; }
uint32_t ledcChangeFrequency(uint8_t pin, uint32_t freq, uint8_t resolution) { return freq; }
unsigned long __micros;
unsigned long __resetTime = 0;

View File

@@ -13,7 +13,7 @@ class SBUS {
public:
SBUS(HardwareSerial& bus, const bool inv = true) {};
SBUS(HardwareSerial& bus, const int8_t rxpin, const int8_t txpin, const bool inv = true) {};
void begin() {};
void begin(int rxpin = -1, int txpin = -1, bool inv = true, bool fast = false) {};
bool read() { return joystickInit(); };
SBUSData data() {
SBUSData data;

View File

@@ -9,6 +9,7 @@
#include "quaternion.h"
#include "Arduino.h"
#include "wifi.h"
#include "lpf.h"
extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
@@ -19,6 +20,7 @@ extern float motors[4];
Vector gyro, acc, imuRotation;
Vector accBias, gyroBias, accScale(1, 1, 1);
LowPassFilter<Vector> gyroBiasFilter(0);
// declarations
void step();
@@ -41,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

@@ -11,9 +11,10 @@
#include <sys/poll.h>
#include <gazebo/gazebo.hh>
#define WIFI_UDP_PORT 14580
#define WIFI_UDP_REMOTE_PORT 14550
#define WIFI_UDP_REMOTE_ADDR "255.255.255.255"
int wifiMode = 1; // mock
int udpLocalPort = 14580;
int udpRemotePort = 14550;
const char *udpRemoteIP = "255.255.255.255";
int wifiSocket;
@@ -22,22 +23,22 @@ void setupWiFi() {
sockaddr_in addr; // local address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = INADDR_ANY;
addr.sin_port = htons(WIFI_UDP_PORT);
addr.sin_port = htons(udpLocalPort);
if (bind(wifiSocket, (sockaddr *)&addr, sizeof(addr))) {
gzerr << "Failed to bind WiFi UDP socket on port " << WIFI_UDP_PORT << std::endl;
gzerr << "Failed to bind WiFi UDP socket on port " << udpLocalPort << std::endl;
return;
}
int broadcast = 1;
setsockopt(wifiSocket, SOL_SOCKET, SO_BROADCAST, &broadcast, sizeof(broadcast)); // enable broadcast
gzmsg << "WiFi UDP socket initialized on port " << WIFI_UDP_PORT << " (remote port " << WIFI_UDP_REMOTE_PORT << ")" << std::endl;
gzmsg << "WiFi UDP socket initialized on port " << udpLocalPort << " (remote port " << udpRemotePort << ")" << std::endl;
}
void sendWiFi(const uint8_t *buf, int len) {
if (wifiSocket == 0) setupWiFi();
sockaddr_in addr; // remote address
addr.sin_family = AF_INET;
addr.sin_addr.s_addr = inet_addr(WIFI_UDP_REMOTE_ADDR);
addr.sin_port = htons(WIFI_UDP_REMOTE_PORT);
addr.sin_addr.s_addr = inet_addr(udpRemoteIP);
addr.sin_port = htons(udpRemotePort);
sendto(wifiSocket, buf, len, 0, (sockaddr *)&addr, sizeof(addr));
}

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()