Compare commits
2 Commits
0547ea548b
...
d6e8be0c05
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
d6e8be0c05 | ||
|
|
68d16855df |
@@ -65,5 +65,6 @@
|
||||
"PX4"
|
||||
]
|
||||
},
|
||||
"MD045": false
|
||||
"MD045": false,
|
||||
"MD060": false
|
||||
}
|
||||
|
||||
BIN
docs/img/imu-axes.png
Normal file
|
After Width: | Height: | Size: 23 KiB |
BIN
docs/img/imu-rot-1.png
Normal file
|
After Width: | Height: | Size: 18 KiB |
BIN
docs/img/imu-rot-2.png
Normal file
|
After Width: | Height: | Size: 18 KiB |
BIN
docs/img/imu-rot-3.png
Normal file
|
After Width: | Height: | Size: 17 KiB |
BIN
docs/img/imu-rot-4.png
Normal file
|
After Width: | Height: | Size: 17 KiB |
BIN
docs/img/imu-rot-5.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
BIN
docs/img/imu-rot-6.png
Normal file
|
After Width: | Height: | Size: 9.6 KiB |
BIN
docs/img/imu-rot-7.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
BIN
docs/img/imu-rot-8.png
Normal file
|
After Width: | Height: | Size: 10 KiB |
@@ -73,14 +73,6 @@ ICM20948 imu(SPI); // For ICM-20948
|
||||
MPU6050 imu(Wire); // For MPU-6050
|
||||
```
|
||||
|
||||
### Setup the IMU orientation
|
||||
|
||||
The IMU orientation is defined in `rotateIMU` function in the `imu.ino` file. Change it so it converts the IMU axes to the drone's axes correctly. **Drone axes are X forward, Y left, Z up**:
|
||||
|
||||
<img src="img/drone-axes.svg" width="200">
|
||||
|
||||
See various [IMU boards axes orientations table](https://github.com/okalachev/flixperiph/?tab=readme-ov-file#imu-axes-orientation) to help you set up the correct orientation.
|
||||
|
||||
### Connect using QGroundControl
|
||||
|
||||
QGroundControl is a ground control station software that can be used to monitor and control the drone.
|
||||
@@ -88,7 +80,7 @@ QGroundControl is a ground control station software that can be used to monitor
|
||||
1. Install mobile or desktop version of [QGroundControl](https://docs.qgroundcontrol.com/master/en/qgc-user-guide/getting_started/download_and_install.html).
|
||||
2. Power up the drone.
|
||||
3. Connect your computer or smartphone to the appeared `flix` Wi-Fi network (password: `flixwifi`).
|
||||
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically
|
||||
4. Launch QGroundControl app. It should connect and begin showing the drone's telemetry automatically.
|
||||
|
||||
### Access console
|
||||
|
||||
@@ -104,11 +96,35 @@ To access the console using QGroundControl:
|
||||
|
||||
1. Connect to the drone using QGroundControl app.
|
||||
2. Go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Analyze Tools* ⇒ *MAVLink Console*.
|
||||
|
||||
<img src="img/cli.png" width="400">
|
||||
|
||||
> [!TIP]
|
||||
> Use `help` command to see the list of available commands.
|
||||
|
||||
### Access parameters
|
||||
|
||||
The drone is configured using parameters. To access and modify them, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*:
|
||||
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
### Define IMU orientation
|
||||
|
||||
Use parameters, to define the IMU board axes orientation relative to the drone's axes: `IMU_ROT_ROLL`, `IMU_ROT_PITCH`, and `IMU_ROT_YAW`.
|
||||
|
||||
The drone has *X* axis pointing forward, *Y* axis pointing left, and *Z* axis pointing up, and the supported IMU boards have *X* axis pointing to the pins side and *Z* axis pointing up from the component side:
|
||||
|
||||
<img src="img/imu-axes.png" width="200">
|
||||
|
||||
Use the following table to set the parameters for common IMU orientations:
|
||||
|
||||
|Orientation|Parameters|Orientation|Parameters|
|
||||
|:-:|-|-|-|
|
||||
|<img src="img/imu-rot-1.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0|
|
||||
|<img src="img/imu-rot-2.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|
|
||||
|<img src="img/imu-rot-3.png" width="180">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|
|
||||
|<img src="img/imu-rot-4.png" width="180"><br>☑️ **Default**|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="180">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
|
||||
|
||||
### Calibrate accelerometer
|
||||
|
||||
Before flight you need to calibrate the accelerometer:
|
||||
@@ -136,6 +152,10 @@ Before flight you need to calibrate the accelerometer:
|
||||
* `mrl` — should rotate rear left motor (counter-clockwise).
|
||||
* `mrr` — should rotate rear right motor (clockwise).
|
||||
|
||||
Rotation diagram:
|
||||
|
||||
<img src="img/motors.svg" width=200>
|
||||
|
||||
> [!WARNING]
|
||||
> Never run the motors when powering the drone from USB, always use the battery for that.
|
||||
|
||||
@@ -221,12 +241,6 @@ In this mode, the pilot inputs are ignored (except the mode switch, if configure
|
||||
|
||||
If the pilot moves the control sticks, the drone will switch back to *STAB* mode.
|
||||
|
||||
## Adjusting parameters
|
||||
|
||||
You can adjust some of the drone's parameters (include PID coefficients) in QGroundControl. In order to do that, go to the QGroundControl menu ⇒ *Vehicle Setup* ⇒ *Parameters*.
|
||||
|
||||
<img src="img/parameters.png" width="400">
|
||||
|
||||
## Flight log
|
||||
|
||||
After the flight, you can download the flight log for analysis wirelessly. Use the following for that:
|
||||
|
||||
15
flix/imu.ino
@@ -10,6 +10,7 @@
|
||||
#include "util.h"
|
||||
|
||||
MPU9250 imu(SPI);
|
||||
Vector imuRotation(0, 0, -PI / 2); // imu orientation as Euler angles
|
||||
|
||||
Vector accBias;
|
||||
Vector accScale(1, 1, 1);
|
||||
@@ -37,16 +38,10 @@ void readIMU() {
|
||||
// apply scale and bias
|
||||
acc = (acc - accBias) / accScale;
|
||||
gyro = gyro - gyroBias;
|
||||
// rotate
|
||||
rotateIMU(acc);
|
||||
rotateIMU(gyro);
|
||||
}
|
||||
|
||||
void rotateIMU(Vector& data) {
|
||||
// Rotate from LFD to FLU
|
||||
// NOTE: In case of using other IMU orientation, change this line:
|
||||
data = Vector(data.y, data.x, -data.z);
|
||||
// Axes orientation for various boards: https://github.com/okalachev/flixperiph#imu-axes-orientation
|
||||
// rotate to body frame
|
||||
Quaternion rotation = Quaternion::fromEuler(imuRotation);
|
||||
acc = Quaternion::rotateVector(acc, rotation.inversed());
|
||||
gyro = Quaternion::rotateVector(gyro, rotation.inversed());
|
||||
}
|
||||
|
||||
void calibrateGyroOnce() {
|
||||
|
||||
@@ -43,6 +43,9 @@ Parameter parameters[] = {
|
||||
{"CTL_Y_RATE_MAX", &maxRate.z},
|
||||
{"CTL_TILT_MAX", &tiltMax},
|
||||
// imu
|
||||
{"IMU_ROT_ROLL", &imuRotation.x},
|
||||
{"IMU_ROT_PITCH", &imuRotation.y},
|
||||
{"IMU_ROT_YAW", &imuRotation.z},
|
||||
{"IMU_ACC_BIAS_X", &accBias.x},
|
||||
{"IMU_ACC_BIAS_Y", &accBias.y},
|
||||
{"IMU_ACC_BIAS_Z", &accBias.z},
|
||||
|
||||
@@ -22,6 +22,7 @@ Vector gyro;
|
||||
Vector rates;
|
||||
Quaternion attitude;
|
||||
bool landed;
|
||||
Vector imuRotation;
|
||||
|
||||
// declarations
|
||||
void step();
|
||||
|
||||