1 Commits

Author SHA1 Message Date
Oleg Kalachev
6c41f65ef9 Apply motors configuration without reboot 2026-01-27 09:56:39 +03:00
23 changed files with 77 additions and 122 deletions

Binary file not shown.

Before

Width:  |  Height:  |  Size: 62 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 48 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 50 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 17 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 44 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 55 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 105 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 34 KiB

Binary file not shown.

Before

Width:  |  Height:  |  Size: 36 KiB

View File

@@ -13,7 +13,7 @@ Do the following:
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 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 or `reboot` command to see the whole 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 to make sure you see the whole ESP32 startup output.
* **Check the baudrate is correct**. If you see garbage characters in the Serial Monitor, make sure the baudrate is set to 115200. * **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. * **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)*. * **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,7 +35,5 @@ Do the following:
* **Check the propeller directions are correct**. Make sure your propeller types (A or B) are installed as on the picture: * **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"> <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. * **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**: * If using SBUS receiver, **calibrate the RC**. Type `cr` command in Serial Monitor and follow the instructions.
* **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. * **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

@@ -146,29 +146,27 @@ If using brushless motors and ESCs:
> [!CAUTION] > [!CAUTION]
> **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them. > **Remove the props when configuring the motors!** If improperly configured, you may not be able to stop them.
### Important: check everything works ### Check everything works
1. Check the IMU is working: perform `imu` command in the console and check the output: 1. Check the IMU is working: perform `imu` command and check its output:
* The `status` field should be `OK`. * The `status` field should be `OK`.
* The `rate` field should be about 1000 (Hz). * The `rate` field should be about 1000 (Hz).
* The `accel` and `gyro` fields should change as you move the drone. * 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. * 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: 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> <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. Use the following commands **— remove the propellers before running the tests!** 3. Perform motor tests in the console. Use the following commands **— remove the propellers before running the tests!**
* `mfr` — rotate front right motor (counter-clockwise). * `mfr` — should rotate front right motor (counter-clockwise).
* `mfl` — rotate front left motor (clockwise). * `mfl` — should rotate front left motor (clockwise).
* `mrl` — rotate rear left motor (counter-clockwise). * `mrl` — should rotate rear left motor (counter-clockwise).
* `mrr` — rotate rear right motor (clockwise). * `mrr` — should rotate rear right motor (clockwise).
Make sure rotation directions and propeller types match the following diagram: Rotation diagram:
<img src="img/motors.svg" width=200> <img src="img/motors.svg" width=200>
@@ -193,13 +191,11 @@ There are several ways to control the drone's flight: using **smartphone** (Wi-F
### Control with a remote control ### Control with a remote control
Before using SBUS-connected remote control you need to enable SBUS and calibrate it: Before using remote SBUS-connected remote control, you need to calibrate it:
1. Connect to the drone using QGroundControl. 1. Access the console using QGroundControl (recommended) or Serial Monitor.
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. 2. Type `cr` command and follow the instructions.
3. Reboot the drone to apply changes. 3. Use the remote control to fly the drone!
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 ### Control with a USB remote control
@@ -236,11 +232,11 @@ When finished flying, **disarm** the drone, moving the left stick to the bottom
### Flight modes ### Flight modes
Flight mode is changed using mode switch on the remote control (if configured) or using the console commands. The main flight mode is *STAB*. Flight mode is changed using mode switch on the remote control or using the command line.
#### STAB #### 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. 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.
> [!IMPORTANT] > [!IMPORTANT]
> The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually. > The drone doesn't stabilize its position, so slight drift is possible. The pilot should compensate it manually.
@@ -255,7 +251,7 @@ In this mode, the pilot controls the angular rates. This control method is diffi
#### AUTO #### AUTO
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. 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.
If the pilot moves the control sticks, the drone will switch back to *STAB* mode. If the pilot moves the control sticks, the drone will switch back to *STAB* mode.

View File

@@ -4,33 +4,6 @@ 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> 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> <img src="img/user/goldarte/1.jpg" height=150> <img src="img/user/goldarte/2.jpg" height=150>

View File

@@ -52,7 +52,6 @@ PID pitchPID(PITCH_P, PITCH_I, PITCH_D);
PID yawPID(YAW_P, 0, 0); PID yawPID(YAW_P, 0, 0);
Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX); Vector maxRate(ROLLRATE_MAX, PITCHRATE_MAX, YAWRATE_MAX);
float tiltMax = TILT_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 const int MOTOR_REAR_LEFT, MOTOR_REAR_RIGHT, MOTOR_FRONT_RIGHT, MOTOR_FRONT_LEFT;
extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode; extern float controlRoll, controlPitch, controlThrottle, controlYaw, controlMode;
@@ -66,9 +65,9 @@ void control() {
} }
void interpretControls() { void interpretControls() {
if (controlMode < 0.25) mode = flightModes[0]; if (controlMode < 0.25) mode = STAB;
else if (controlMode < 0.75) mode = flightModes[1]; if (controlMode < 0.75) mode = STAB;
else if (controlMode > 0.75) mode = flightModes[2]; if (controlMode > 0.75) mode = STAB;
if (mode == AUTO) return; // pilot is not effective in AUTO mode 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> // Copyright (c) 2023 Oleg Kalachev <okalachev@gmail.com>
// Repository: https://github.com/okalachev/flix // Repository: https://github.com/okalachev/flix
// Attitude estimation using gyro and accelerometer // Attitude estimation from gyro and accelerometer
#include "quaternion.h" #include "quaternion.h"
#include "vector.h" #include "vector.h"

View File

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

View File

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

View File

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

View File

@@ -6,23 +6,21 @@
#include <Preferences.h> #include <Preferences.h>
#include "util.h" #include "util.h"
extern int channelZero[16]; extern float channelZero[16];
extern int channelMax[16]; extern float channelMax[16];
extern int rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel; extern float rollChannel, pitchChannel, throttleChannel, yawChannel, armedChannel, modeChannel;
extern int rcRxPin;
extern int wifiMode, udpLocalPort, udpRemotePort; extern int wifiMode, udpLocalPort, udpRemotePort;
extern float rcLossTimeout, descendTime; extern float rcLossTimeout, descendTime;
Preferences storage; Preferences storage;
struct Parameter { struct Parameter {
const char *name; // max length is 15 const char *name; // max length is 15 (Preferences key limit)
bool integer; bool integer;
union { float *f; int *i; }; // pointer to the variable union { float *f; int *i; }; // pointer to variable
float cache; // what's stored in flash float cache; // what's stored in flash
void (*callback)(); // called after parameter change Parameter(const char *name, float *variable) : name(name), integer(false), f(variable) {};
Parameter(const char *name, float *variable, void (*callback)() = nullptr) : name(name), integer(false), f(variable), callback(callback) {}; Parameter(const char *name, int *variable) : name(name), integer(true), i(variable) {};
Parameter(const char *name, int *variable, void (*callback)() = nullptr) : name(name), integer(true), i(variable), callback(callback) {};
float getValue() const { return integer ? *i : *f; }; float getValue() const { return integer ? *i : *f; };
void setValue(const float value) { if (integer) *i = value; else *f = value; }; void setValue(const float value) { if (integer) *i = value; else *f = value; };
}; };
@@ -51,9 +49,6 @@ Parameter parameters[] = {
{"CTL_R_RATE_MAX", &maxRate.x}, {"CTL_R_RATE_MAX", &maxRate.x},
{"CTL_Y_RATE_MAX", &maxRate.z}, {"CTL_Y_RATE_MAX", &maxRate.z},
{"CTL_TILT_MAX", &tiltMax}, {"CTL_TILT_MAX", &tiltMax},
{"CTL_FLT_MODE_0", &flightModes[0]},
{"CTL_FLT_MODE_1", &flightModes[1]},
{"CTL_FLT_MODE_2", &flightModes[2]},
// imu // imu
{"IMU_ROT_ROLL", &imuRotation.x}, {"IMU_ROT_ROLL", &imuRotation.x},
{"IMU_ROT_PITCH", &imuRotation.y}, {"IMU_ROT_PITCH", &imuRotation.y},
@@ -69,17 +64,16 @@ Parameter parameters[] = {
{"EST_ACC_WEIGHT", &accWeight}, {"EST_ACC_WEIGHT", &accWeight},
{"EST_RATES_LPF_A", &ratesFilter.alpha}, {"EST_RATES_LPF_A", &ratesFilter.alpha},
// motors // motors
{"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT], setupMotors}, {"MOT_PIN_FL", &motorPins[MOTOR_FRONT_LEFT]},
{"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT], setupMotors}, {"MOT_PIN_FR", &motorPins[MOTOR_FRONT_RIGHT]},
{"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT], setupMotors}, {"MOT_PIN_RL", &motorPins[MOTOR_REAR_LEFT]},
{"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT], setupMotors}, {"MOT_PIN_RR", &motorPins[MOTOR_REAR_RIGHT]},
{"MOT_PWM_FREQ", &pwmFrequency, setupMotors}, {"MOT_PWM_FREQ", &pwmFrequency},
{"MOT_PWM_RES", &pwmResolution, setupMotors}, {"MOT_PWM_RES", &pwmResolution},
{"MOT_PWM_STOP", &pwmStop}, {"MOT_PWM_STOP", &pwmStop},
{"MOT_PWM_MIN", &pwmMin}, {"MOT_PWM_MIN", &pwmMin},
{"MOT_PWM_MAX", &pwmMax}, {"MOT_PWM_MAX", &pwmMax},
// rc // rc
{"RC_RX_PIN", &rcRxPin},
{"RC_ZERO_0", &channelZero[0]}, {"RC_ZERO_0", &channelZero[0]},
{"RC_ZERO_1", &channelZero[1]}, {"RC_ZERO_1", &channelZero[1]},
{"RC_ZERO_2", &channelZero[2]}, {"RC_ZERO_2", &channelZero[2]},
@@ -115,8 +109,7 @@ Parameter parameters[] = {
}; };
void setupParameters() { void setupParameters() {
print("Setup parameters\n"); storage.begin("flix", false);
storage.begin("flix");
// Read parameters from storage // Read parameters from storage
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (!storage.isKey(parameter.name)) { if (!storage.isKey(parameter.name)) {
@@ -127,6 +120,11 @@ void setupParameters() {
} }
} }
void afterParameterChange(String name, const float value) {
if (name == "MOT_PWM_FREQ" || name == "MOT_PWM_RES") setupMotors();
if (name == "MOT_PIN_FL" || name == "MOT_PIN_FR" || name == "MOT_PIN_RL" || name == "MOT_PIN_RR") setupMotors();
}
int parametersCount() { int parametersCount() {
return sizeof(parameters) / sizeof(parameters[0]); return sizeof(parameters) / sizeof(parameters[0]);
} }
@@ -155,7 +153,7 @@ bool setParameter(const char *name, const float value) {
if (strcasecmp(parameter.name, name) == 0) { if (strcasecmp(parameter.name, name) == 0) {
if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf if (parameter.integer && !isfinite(value)) return false; // can't set integer to NaN or Inf
parameter.setValue(value); parameter.setValue(value);
if (parameter.callback) parameter.callback(); afterParameterChange(name, value);
return true; return true;
} }
} }
@@ -169,7 +167,8 @@ void syncParameters() {
for (auto &parameter : parameters) { for (auto &parameter : parameters) {
if (parameter.getValue() == parameter.cache) continue; // no change if (parameter.getValue() == parameter.cache) continue; // no change
if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NAN if (isnan(parameter.getValue()) && isnan(parameter.cache)) continue; // both are NaN
if (isinf(parameter.getValue()) && isinf(parameter.cache)) continue; // both are Inf
storage.putFloat(parameter.name, parameter.getValue()); storage.putFloat(parameter.name, parameter.getValue());
parameter.cache = parameter.getValue(); // update cache parameter.cache = parameter.getValue(); // update cache

View File

@@ -7,26 +7,24 @@
#include "util.h" #include "util.h"
SBUS rc(Serial2); SBUS rc(Serial2);
int rcRxPin = -1; // -1 means disabled
uint16_t channels[16]; // raw rc channels uint16_t channels[16]; // raw rc channels
int channelZero[16]; // calibration zero values float channelZero[16]; // calibration zero values
int channelMax[16]; // calibration max values float channelMax[16]; // calibration max values
float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1] float controlRoll, controlPitch, controlYaw, controlThrottle; // pilot's inputs, range [-1, 1]
float controlMode = NAN; float controlMode = NAN;
float controlTime = NAN; // time of the last controls update float controlTime = NAN; // time of the last controls update
int rollChannel = -1, pitchChannel = -1, throttleChannel = -1, yawChannel = -1, modeChannel = -1; // channel mapping // Channels mapping (nan means not assigned):
float rollChannel = NAN, pitchChannel = NAN, throttleChannel = NAN, yawChannel = NAN, modeChannel = NAN;
void setupRC() { void setupRC() {
if (rcRxPin < 0) return;
print("Setup RC\n"); print("Setup RC\n");
rc.begin(rcRxPin); rc.begin();
} }
bool readRC() { bool readRC() {
if (rcRxPin < 0) return false;
if (rc.read()) { if (rc.read()) {
SBUSData data = rc.data(); SBUSData data = rc.data();
for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data for (int i = 0; i < 16; i++) channels[i] = data.ch[i]; // copy channels data
@@ -43,18 +41,14 @@ void normalizeRC() {
controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1); controls[i] = mapf(channels[i], channelZero[i], channelMax[i], 0, 1);
} }
// Update control values // Update control values
controlRoll = rollChannel < 0 ? 0 : controls[rollChannel]; controlRoll = rollChannel >= 0 ? controls[(int)rollChannel] : 0;
controlPitch = pitchChannel < 0 ? 0 : controls[pitchChannel]; controlPitch = pitchChannel >= 0 ? controls[(int)pitchChannel] : 0;
controlYaw = yawChannel < 0 ? 0 : controls[yawChannel]; controlYaw = yawChannel >= 0 ? controls[(int)yawChannel] : 0;
controlThrottle = throttleChannel < 0 ? 0 : controls[throttleChannel]; controlThrottle = throttleChannel >= 0 ? controls[(int)throttleChannel] : 0;
controlMode = modeChannel < 0 ? NAN : controls[modeChannel]; // mode control is ineffective if not mapped controlMode = modeChannel >= 0 ? controls[(int)modeChannel] : NAN; // mode switch should not have affect if not set
} }
void calibrateRC() { void calibrateRC() {
if (rcRxPin < 0) {
print("RC_RX_PIN = %d, set the RC pin!\n", rcRxPin);
return;
}
uint16_t zero[16]; uint16_t zero[16];
uint16_t center[16]; uint16_t center[16];
uint16_t max[16]; uint16_t max[16];
@@ -70,7 +64,7 @@ void calibrateRC() {
printRCCalibration(); printRCCalibration();
} }
void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const char *str) { void calibrateRCChannel(float *channel, uint16_t in[16], uint16_t out[16], const char *str) {
print("%s", str); print("%s", str);
pause(3); pause(3);
for (int i = 0; i < 30; i++) readRC(); // try update 30 times max for (int i = 0; i < 30; i++) readRC(); // try update 30 times max
@@ -91,15 +85,15 @@ void calibrateRCChannel(int *channel, uint16_t in[16], uint16_t out[16], const c
channelZero[ch] = in[ch]; channelZero[ch] = in[ch];
channelMax[ch] = out[ch]; channelMax[ch] = out[ch];
} else { } else {
*channel = -1; *channel = NAN;
} }
} }
void printRCCalibration() { void printRCCalibration() {
print("Control Ch Zero Max\n"); print("Control Ch Zero Max\n");
print("Roll %-7d%-7d%-7d\n", rollChannel, rollChannel < 0 ? 0 : channelZero[rollChannel], rollChannel < 0 ? 0 : channelMax[rollChannel]); print("Roll %-7g%-7g%-7g\n", rollChannel, rollChannel >= 0 ? channelZero[(int)rollChannel] : NAN, rollChannel >= 0 ? channelMax[(int)rollChannel] : NAN);
print("Pitch %-7d%-7d%-7d\n", pitchChannel, pitchChannel < 0 ? 0 : channelZero[pitchChannel], pitchChannel < 0 ? 0 : channelMax[pitchChannel]); print("Pitch %-7g%-7g%-7g\n", pitchChannel, pitchChannel >= 0 ? channelZero[(int)pitchChannel] : NAN, pitchChannel >= 0 ? channelMax[(int)pitchChannel] : NAN);
print("Yaw %-7d%-7d%-7d\n", yawChannel, yawChannel < 0 ? 0 : channelZero[yawChannel], yawChannel < 0 ? 0 : channelMax[yawChannel]); print("Yaw %-7g%-7g%-7g\n", yawChannel, yawChannel >= 0 ? channelZero[(int)yawChannel] : NAN, yawChannel >= 0 ? channelMax[(int)yawChannel] : NAN);
print("Throttle %-7d%-7d%-7d\n", throttleChannel, throttleChannel < 0 ? 0 : channelZero[throttleChannel], throttleChannel < 0 ? 0 : channelMax[throttleChannel]); print("Throttle %-7g%-7g%-7g\n", throttleChannel, throttleChannel >= 0 ? channelZero[(int)throttleChannel] : NAN, throttleChannel >= 0 ? channelMax[(int)throttleChannel] : NAN);
print("Mode %-7d%-7d%-7d\n", modeChannel, modeChannel < 0 ? 0 : channelZero[modeChannel], modeChannel < 0 ? 0 : channelMax[modeChannel]); print("Mode %-7g%-7g%-7g\n", modeChannel, modeChannel >= 0 ? channelZero[(int)modeChannel] : NAN, modeChannel >= 0 ? channelMax[(int)modeChannel] : NAN);
} }

View File

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

View File

@@ -9,7 +9,6 @@
#include "quaternion.h" #include "quaternion.h"
#include "Arduino.h" #include "Arduino.h"
#include "wifi.h" #include "wifi.h"
#include "lpf.h"
extern float t, dt; extern float t, dt;
extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode; extern float controlRoll, controlPitch, controlYaw, controlThrottle, controlMode;
@@ -20,7 +19,6 @@ extern float motors[4];
Vector gyro, acc, imuRotation; Vector gyro, acc, imuRotation;
Vector accBias, gyroBias, accScale(1, 1, 1); Vector accBias, gyroBias, accScale(1, 1, 1);
LowPassFilter<Vector> gyroBiasFilter(0);
// declarations // declarations
void step(); void step();
@@ -43,7 +41,7 @@ void doCommand(String str, bool echo);
void handleInput(); void handleInput();
void normalizeRC(); void normalizeRC();
void calibrateRC(); void calibrateRC();
void calibrateRCChannel(int *channel, uint16_t zero[16], uint16_t max[16], const char *str); void calibrateRCChannel(float *channel, uint16_t zero[16], uint16_t max[16], const char *str);
void printRCCalibration(); void printRCCalibration();
void printLogHeader(); void printLogHeader();
void printLogData(); void printLogData();

View File

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

View File

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