aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/gyro_calibration.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/modules/commander/gyro_calibration.cpp')
-rw-r--r--src/modules/commander/gyro_calibration.cpp270
1 files changed, 139 insertions, 131 deletions
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 369e6da62..30cd0d48d 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -33,10 +33,12 @@
/**
* @file gyro_calibration.cpp
+ *
* Gyroscope calibration routine
*/
#include "gyro_calibration.h"
+#include "calibration_messages.h"
#include "commander_helper.h"
#include <stdio.h>
@@ -56,21 +58,14 @@
#endif
static const int ERROR = -1;
+static const char *sensor_name = "gyro";
+
int do_gyro_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "Gyro calibration starting, do not move unit.");
-
- const unsigned calibration_count = 5000;
-
- int sub_sensor_combined = orb_subscribe(ORB_ID(sensor_combined));
- struct sensor_combined_s raw;
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "don't move system");
- unsigned calibration_counter = 0;
- float gyro_offset[3] = {0.0f, 0.0f, 0.0f};
-
- /* set offsets to zero */
- int fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale_null = {
+ struct gyro_scale gyro_scale = {
0.0f,
1.0f,
0.0f,
@@ -79,97 +74,100 @@ int do_gyro_calibration(int mavlink_fd)
1.0f,
};
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale_null))
- warn("WARNING: failed to set scale / offsets for gyro");
+ int res = OK;
+ /* reset all offsets to zero and all scales to one */
+ int fd = open(GYRO_DEVICE_PATH, 0);
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
close(fd);
- unsigned poll_errcount = 0;
-
- while (calibration_counter < calibration_count) {
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
- /* wait blocking for new data */
- struct pollfd fds[1];
- fds[0].fd = sub_sensor_combined;
- fds[0].events = POLLIN;
+ if (res == OK) {
+ /* determine gyro mean values */
+ const unsigned calibration_count = 5000;
+ unsigned calibration_counter = 0;
+ unsigned poll_errcount = 0;
+
+ /* subscribe to gyro sensor topic */
+ int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro));
+ struct gyro_report gyro_report;
+
+ while (calibration_counter < calibration_count) {
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_sensor_gyro;
+ fds[0].events = POLLIN;
+
+ int poll_ret = poll(fds, 1, 1000);
+
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_gyro), sub_sensor_gyro, &gyro_report);
+ gyro_scale.x_offset += gyro_report.x;
+ gyro_scale.y_offset += gyro_report.y;
+ gyro_scale.z_offset += gyro_report.z;
+ calibration_counter++;
+
+ if (calibration_counter % (calibration_count / 20) == 0)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, (calibration_counter * 100) / calibration_count);
+
+ } else {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ res = ERROR;
+ break;
+ }
+ }
- int poll_ret = poll(fds, 1, 1000);
+ close(sub_sensor_gyro);
- if (poll_ret > 0) {
- orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
- gyro_offset[0] += raw.gyro_rad_s[0];
- gyro_offset[1] += raw.gyro_rad_s[1];
- gyro_offset[2] += raw.gyro_rad_s[2];
- calibration_counter++;
- if (calibration_counter % (calibration_count / 20) == 0)
- mavlink_log_info(mavlink_fd, "gyro cal progress <%u> percent", (calibration_counter * 100) / calibration_count);
-
- } else {
- poll_errcount++;
- }
+ gyro_scale.x_offset /= calibration_count;
+ gyro_scale.y_offset /= calibration_count;
+ gyro_scale.z_offset /= calibration_count;
+ }
- if (poll_errcount > 1000) {
- mavlink_log_info(mavlink_fd, "ERROR: Failed reading gyro sensor");
- close(sub_sensor_combined);
- return ERROR;
+ if (res == OK) {
+ /* check offsets */
+ if (!isfinite(gyro_scale.x_offset) || !isfinite(gyro_scale.y_offset) || !isfinite(gyro_scale.z_offset)) {
+ mavlink_log_critical(mavlink_fd, "ERROR: offset is NaN");
+ res = ERROR;
}
}
- gyro_offset[0] = gyro_offset[0] / calibration_count;
- gyro_offset[1] = gyro_offset[1] / calibration_count;
- gyro_offset[2] = gyro_offset[2] / calibration_count;
-
-
- if (isfinite(gyro_offset[0]) && isfinite(gyro_offset[1]) && isfinite(gyro_offset[2])) {
-
- if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_offset[0]))
- || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_offset[1]))
- || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_offset[2]))) {
- mavlink_log_critical(mavlink_fd, "Setting gyro offsets failed!");
+ if (res == OK) {
+ /* set offset parameters to new values */
+ if (param_set(param_find("SENS_GYRO_XOFF"), &(gyro_scale.x_offset))
+ || param_set(param_find("SENS_GYRO_YOFF"), &(gyro_scale.y_offset))
+ || param_set(param_find("SENS_GYRO_ZOFF"), &(gyro_scale.z_offset))) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set offset params");
+ res = ERROR;
}
+ }
- /* set offsets to actual value */
- fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale = {
- gyro_offset[0],
- 1.0f,
- gyro_offset[1],
- 1.0f,
- gyro_offset[2],
- 1.0f,
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
- warn("WARNING: failed to set scale / offsets for gyro");
-
- close(fd);
+#if 0
+ /* beep on offset calibration end */
+ mavlink_log_info(mavlink_fd, "gyro offset calibration done");
+ tune_neutral();
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
+ /* scale calibration */
+ /* this was only a proof of concept and is currently not working. scaling will be set to 1.0 for now. */
- if (save_ret != 0) {
- warnx("WARNING: auto-save of params to storage failed");
- mavlink_log_critical(mavlink_fd, "gyro store failed");
- close(sub_sensor_combined);
- return ERROR;
- }
+ mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip.");
+ warnx("offset calibration finished. Rotate for scale 30x, or do not rotate and wait for 5 seconds to skip.");
- tune_neutral();
- /* third beep by cal end routine */
+ /* apply new offsets */
+ fd = open(GYRO_DEVICE_PATH, 0);
- } else {
- mavlink_log_info(mavlink_fd, "offset cal FAILED (NaN)");
- close(sub_sensor_combined);
- return ERROR;
- }
+ if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
+ warn("WARNING: failed to apply new offsets for gyro");
- mavlink_log_info(mavlink_fd, "offset calibration done.");
+ close(fd);
-#if 0
- /*** --- SCALING --- ***/
-
- mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip.");
- warnx("offset calibration finished. Rotate for scale 30x, or do not rotate and wait for 5 seconds to skip.");
unsigned rotations_count = 30;
float gyro_integral = 0.0f;
@@ -178,9 +176,11 @@ int do_gyro_calibration(int mavlink_fd)
// XXX change to mag topic
orb_copy(ORB_ID(sensor_combined), sub_sensor_combined, &raw);
- float mag_last = -atan2f(raw.magnetometer_ga[1],raw.magnetometer_ga[0]);
- if (mag_last > M_PI_F) mag_last -= 2*M_PI_F;
- if (mag_last < -M_PI_F) mag_last += 2*M_PI_F;
+ float mag_last = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
+
+ if (mag_last > M_PI_F) mag_last -= 2 * M_PI_F;
+
+ if (mag_last < -M_PI_F) mag_last += 2 * M_PI_F;
uint64_t last_time = hrt_absolute_time();
@@ -190,7 +190,7 @@ int do_gyro_calibration(int mavlink_fd)
/* abort this loop if not rotated more than 180 degrees within 5 seconds */
if ((fabsf(baseline_integral / (2.0f * M_PI_F)) < 0.6f)
- && (hrt_absolute_time() - start_time > 5 * 1e6)) {
+ && (hrt_absolute_time() - start_time > 5 * 1e6)) {
mavlink_log_info(mavlink_fd, "scale skipped, gyro calibration done");
close(sub_sensor_combined);
return OK;
@@ -218,14 +218,17 @@ int do_gyro_calibration(int mavlink_fd)
// calculate error between estimate and measurement
// apply declination correction for true heading as well.
//float mag = -atan2f(magNav(1),magNav(0));
- float mag = -atan2f(raw.magnetometer_ga[1],raw.magnetometer_ga[0]);
- if (mag > M_PI_F) mag -= 2*M_PI_F;
- if (mag < -M_PI_F) mag += 2*M_PI_F;
+ float mag = -atan2f(raw.magnetometer_ga[1], raw.magnetometer_ga[0]);
+
+ if (mag > M_PI_F) mag -= 2 * M_PI_F;
+
+ if (mag < -M_PI_F) mag += 2 * M_PI_F;
float diff = mag - mag_last;
- if (diff > M_PI_F) diff -= 2*M_PI_F;
- if (diff < -M_PI_F) diff += 2*M_PI_F;
+ if (diff > M_PI_F) diff -= 2 * M_PI_F;
+
+ if (diff < -M_PI_F) diff += 2 * M_PI_F;
baseline_integral += diff;
mag_last = mag;
@@ -235,63 +238,68 @@ int do_gyro_calibration(int mavlink_fd)
// warnx("dbg: b: %6.4f, g: %6.4f", (double)baseline_integral, (double)gyro_integral);
- // } else if (poll_ret == 0) {
- // /* any poll failure for 1s is a reason to abort */
- // mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
- // return;
+ // } else if (poll_ret == 0) {
+ // /* any poll failure for 1s is a reason to abort */
+ // mavlink_log_info(mavlink_fd, "gyro calibration aborted, retry");
+ // return;
}
}
float gyro_scale = baseline_integral / gyro_integral;
-
+
warnx("gyro scale: yaw (z): %6.4f", (double)gyro_scale);
mavlink_log_info(mavlink_fd, "gyro scale: yaw (z): %6.4f", (double)gyro_scale);
-#else
- float gyro_scales[] = { 1.0f, 1.0f, 1.0f };
-#endif
-
+ if (!isfinite(gyro_scale.x_scale) || !isfinite(gyro_scale.y_scale) || !isfinite(gyro_scale.z_scale)) {
+ mavlink_log_info(mavlink_fd, "gyro scale calibration FAILED (NaN)");
+ close(sub_sensor_gyro);
+ mavlink_log_critical(mavlink_fd, "gyro calibration failed");
+ return ERROR;
+ }
- if (isfinite(gyro_scales[0]) && isfinite(gyro_scales[1]) && isfinite(gyro_scales[2])) {
+ /* beep on calibration end */
+ mavlink_log_info(mavlink_fd, "gyro scale calibration done");
+ tune_neutral();
- if (param_set(param_find("SENS_GYRO_XSCALE"), &(gyro_scales[0]))
- || param_set(param_find("SENS_GYRO_YSCALE"), &(gyro_scales[1]))
- || param_set(param_find("SENS_GYRO_ZSCALE"), &(gyro_scales[2]))) {
- mavlink_log_critical(mavlink_fd, "Setting gyro scale failed!");
+#endif
+
+ if (res == OK) {
+ /* set scale parameters to new values */
+ if (param_set(param_find("SENS_GYRO_XSCALE"), &(gyro_scale.x_scale))
+ || param_set(param_find("SENS_GYRO_YSCALE"), &(gyro_scale.y_scale))
+ || param_set(param_find("SENS_GYRO_ZSCALE"), &(gyro_scale.z_scale))) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set scale params");
+ res = ERROR;
}
+ }
- /* set offsets to actual value */
+ if (res == OK) {
+ /* apply new scaling and offsets */
fd = open(GYRO_DEVICE_PATH, 0);
- struct gyro_scale gscale = {
- gyro_offset[0],
- gyro_scales[0],
- gyro_offset[1],
- gyro_scales[1],
- gyro_offset[2],
- gyro_scales[2],
- };
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale))
- warn("WARNING: failed to set scale / offsets for gyro");
-
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
close(fd);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
+ }
+
+ if (res == OK) {
/* auto-save to EEPROM */
- int save_ret = param_save_default();
+ res = param_save_default();
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
}
+ }
- mavlink_log_info(mavlink_fd, "gyro calibration done");
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
- /* third beep by cal end routine */
- close(sub_sensor_combined);
- return OK;
} else {
- mavlink_log_info(mavlink_fd, "gyro calibration FAILED (NaN)");
- close(sub_sensor_combined);
- return ERROR;
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
}
+
+ return res;
}