2 Commits

Author SHA1 Message Date
Oleg Kalachev
4d70018d73 Add level calibration 2025-12-26 08:17:59 +03:00
Oleg Kalachev
13a7e67b92 Add parameters for IMU orientation definition 2025-12-26 06:29:19 +03:00
5 changed files with 14 additions and 3 deletions

View File

@@ -65,5 +65,6 @@
"PX4"
]
},
"MD045": false
"MD045": false,
"MD060": false
}

View File

@@ -96,7 +96,8 @@ 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">
<img src="img/cli.png" width="400">
> [!TIP]
> Use `help` command to see the list of available commands.
@@ -122,7 +123,7 @@ Use the following table to set the parameters for common IMU orientations:
|<img src="img/imu-rot-1.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0 |<img src="img/imu-rot-5.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 0|
|<img src="img/imu-rot-2.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|<img src="img/imu-rot-6.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|
|<img src="img/imu-rot-3.png" width="200">|`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|<img src="img/imu-rot-7.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 3.142|
|<img src="img/imu-rot-4.png" width="200"><br><b style="text-align:center">☑️ Default</b>|<br>`IMU_ROT_ROLL` = 0<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = -1.571|<img src="img/imu-rot-8.png" width="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
|<img src="img/imu-rot-4.png" width="200"><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="200">|`IMU_ROT_ROLL` = 3.142<br>`IMU_ROT_PITCH` = 0<br>`IMU_ROT_YAW` = 1.571|
### Calibrate accelerometer

View File

@@ -42,6 +42,7 @@ const char* motd =
"log [dump] - print log header [and data]\n"
"cr - calibrate RC\n"
"ca - calibrate accel\n"
"cl - calibrate level\n"
"mfr, mfl, mrr, mrl - test motor (remove props)\n"
"sys - show system info\n"
"reset - reset drone's state\n"

View File

@@ -44,6 +44,13 @@ void readIMU() {
gyro = Quaternion::rotateVector(gyro, rotation.inversed());
}
void calibrateLevel() {
print("Place perfectly level [1 sec]\n");
pause(1);
Quaternion correction = Quaternion::fromBetweenVectors(Quaternion::rotateVector(Vector(0, 0, 1), attitude), Vector(0, 0, 1));
imuRotation = Quaternion::rotate(correction, Quaternion::fromEuler(imuRotation)).toEuler();
print("✓ Done: %.3f %.3f %.3f\n", degrees(imuRotation.x), degrees(imuRotation.y), degrees(imuRotation.z));
}
void calibrateGyroOnce() {
static Delay landedDelay(2);

View File

@@ -22,6 +22,7 @@ Vector gyro;
Vector rates;
Quaternion attitude;
bool landed;
Vector imuRotation;
// declarations
void step();