aboutsummaryrefslogtreecommitdiff
path: root/src/modules/commander/gyro_calibration.cpp
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-10-21 20:07:47 +0200
committerAnton Babushkin <anton.babushkin@me.com>2013-10-21 20:07:47 +0200
commitea89f23c917733f8a682c82e24e1e4f223f79843 (patch)
treeadbe03a75e28a78bd84f70fb959ccadf8ce9bc7a /src/modules/commander/gyro_calibration.cpp
parented79b686c57f41d9d6bd3726fe0071e11740b3d7 (diff)
downloadpx4-firmware-ea89f23c917733f8a682c82e24e1e4f223f79843.tar.gz
px4-firmware-ea89f23c917733f8a682c82e24e1e4f223f79843.tar.bz2
px4-firmware-ea89f23c917733f8a682c82e24e1e4f223f79843.zip
calibration: bugs fixed, mavlink messages cleanup
Diffstat (limited to 'src/modules/commander/gyro_calibration.cpp')
-rw-r--r--src/modules/commander/gyro_calibration.cpp211
1 files changed, 117 insertions, 94 deletions
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index e1d6e8340..219ae6cb2 100644
--- a/src/modules/commander/gyro_calibration.cpp
+++ b/src/modules/commander/gyro_calibration.cpp
@@ -58,7 +58,7 @@ static const int ERROR = -1;
int do_gyro_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "Gyro calibration starting, do not move unit.");
+ mavlink_log_info(mavlink_fd, "gyro calibration: started");
struct gyro_scale gyro_scale = {
0.0f,
@@ -69,79 +69,85 @@ int do_gyro_calibration(int mavlink_fd)
1.0f,
};
- /* subscribe to gyro sensor topic */
- int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro));
- struct gyro_report gyro_report;
+ int res = OK;
/* reset all offsets to zero and all scales to one */
int fd = open(GYRO_DEVICE_PATH, 0);
-
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
- warn("WARNING: failed to reset scale / offsets for gyro");
-
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
close(fd);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to reset scale / offsets");
+ }
- /*** --- OFFSETS --- ***/
-
- /* determine gyro mean values */
- const unsigned calibration_count = 5000;
- unsigned calibration_counter = 0;
- unsigned poll_errcount = 0;
-
- 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);
+ /* subscribe to gyro sensor topic */
+ int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro));
+ struct gyro_report gyro_report;
- 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, "gyro cal progress <%u> percent", (calibration_counter * 100) / calibration_count);
-
- } else {
- poll_errcount++;
+ if (res == OK) {
+ /* determine gyro mean values */
+ const unsigned calibration_count = 5000;
+ unsigned calibration_counter = 0;
+ unsigned poll_errcount = 0;
+
+ 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, "gyro calibration: progress <%u>", (calibration_counter * 100) / calibration_count);
+
+ } else {
+ poll_errcount++;
+ }
+
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed reading gyro sensor");
+ res = ERROR;
+ break;
+ }
}
- if (poll_errcount > 1000) {
- mavlink_log_info(mavlink_fd, "ERROR: Failed reading gyro sensor");
- close(sub_sensor_gyro);
- return ERROR;
- }
+ gyro_scale.x_offset /= calibration_count;
+ gyro_scale.y_offset /= calibration_count;
+ gyro_scale.z_offset /= calibration_count;
}
- gyro_scale.x_offset /= calibration_count;
- gyro_scale.y_offset /= calibration_count;
- gyro_scale.z_offset /= calibration_count;
-
- if (!isfinite(gyro_scale.x_offset) || !isfinite(gyro_scale.y_offset) || !isfinite(gyro_scale.z_offset)) {
- mavlink_log_info(mavlink_fd, "gyro offset calibration FAILED (NaN)");
- close(sub_sensor_gyro);
- 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;
+ }
}
- /* beep on calibration end */
- mavlink_log_info(mavlink_fd, "gyro offset calibration done.");
- tune_neutral();
-
- /* 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, "Setting gyro offset parameters 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: setting gyro offs params failed");
+ res = ERROR;
+ }
}
-
- /*** --- SCALING --- ***/
#if 0
+ /* beep on offset calibration end */
+ mavlink_log_info(mavlink_fd, "gyro offset calibration done");
+ tune_neutral();
+
+ /* scale calibration */
/* this was only a proof of concept and is currently not working. scaling will be set to 1.0 for now. */
mavlink_log_info(mavlink_fd, "offset done. Rotate for scale 30x or wait 5s to skip.");
@@ -163,9 +169,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();
@@ -175,7 +183,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;
@@ -203,14 +211,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;
@@ -220,15 +231,15 @@ 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);
@@ -236,42 +247,54 @@ int do_gyro_calibration(int mavlink_fd)
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;
}
/* beep on calibration end */
- mavlink_log_info(mavlink_fd, "gyro scale calibration done.");
+ mavlink_log_info(mavlink_fd, "gyro scale calibration done");
tune_neutral();
#endif
- /* 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, "Setting gyro scale parameters failed!");
- }
+ close(sub_sensor_gyro);
- /* apply new scaling and offsets */
- fd = open(GYRO_DEVICE_PATH, 0);
+ 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: setting gyro scale params failed");
+ res = ERROR;
+ }
+ }
- if (OK != ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale))
- warn("WARNING: failed to apply new scale for gyro");
+ if (res == OK) {
+ /* apply new scaling and offsets */
+ fd = open(GYRO_DEVICE_PATH, 0);
+ res = ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale);
+ close(fd);
- close(fd);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to apply new params for gyro");
+ }
+ }
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
+ if (res == OK) {
+ /* auto-save to EEPROM */
+ res = param_save_default();
- if (save_ret != 0) {
- warnx("WARNING: auto-save of params to storage failed");
- mavlink_log_critical(mavlink_fd, "gyro store failed");
- close(sub_sensor_gyro);
- return ERROR;
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to save parameters");
+ }
}
- mavlink_log_info(mavlink_fd, "gyro calibration done.");
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, "gyro calibration: done");
- close(sub_sensor_gyro);
- return OK;
+ } else {
+ mavlink_log_info(mavlink_fd, "gyro calibration: failed");
+ }
+
+ return res;
}