aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--src/modules/commander/accelerometer_calibration.cpp40
-rw-r--r--src/modules/commander/calibration_messages.h57
-rw-r--r--src/modules/commander/gyro_calibration.cpp37
-rw-r--r--src/modules/commander/mag_calibration.cpp276
4 files changed, 239 insertions, 171 deletions
diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp
index d11d7eb5d..49a8d6b33 100644
--- a/src/modules/commander/accelerometer_calibration.cpp
+++ b/src/modules/commander/accelerometer_calibration.cpp
@@ -122,6 +122,7 @@
*/
#include "accelerometer_calibration.h"
+#include "calibration_messages.h"
#include "commander_helper.h"
#include <unistd.h>
@@ -147,6 +148,8 @@
#endif
static const int ERROR = -1;
+static const char *sensor_name = "accel";
+
int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float accel_T[3][3]);
int detect_orientation(int mavlink_fd, int sub_sensor_combined);
int read_accelerometer_avg(int sensor_combined_sub, float accel_avg[3], int samples_num);
@@ -155,8 +158,7 @@ int calculate_calibration_values(float accel_ref[6][3], float accel_T[3][3], flo
int do_accel_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "accel calibration: started");
- mavlink_log_info(mavlink_fd, "accel calibration: progress <0>");
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
struct accel_scale accel_scale = {
0.0f,
@@ -175,7 +177,7 @@ int do_accel_calibration(int mavlink_fd)
close(fd);
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to reset scale / offsets");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
}
/* measure and calculate offsets & scales */
@@ -213,7 +215,7 @@ int do_accel_calibration(int mavlink_fd)
|| param_set(param_find("SENS_ACC_XSCALE"), &(accel_scale.x_scale))
|| param_set(param_find("SENS_ACC_YSCALE"), &(accel_scale.y_scale))
|| param_set(param_find("SENS_ACC_ZSCALE"), &(accel_scale.z_scale))) {
- mavlink_log_critical(mavlink_fd, "ERROR: setting accel params failed");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
res = ERROR;
}
}
@@ -225,7 +227,7 @@ int do_accel_calibration(int mavlink_fd)
close(fd);
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to apply new params for accel");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
}
}
@@ -234,15 +236,15 @@ int do_accel_calibration(int mavlink_fd)
res = param_save_default();
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to save parameters");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
}
}
if (res == OK) {
- mavlink_log_info(mavlink_fd, "accel calibration: done");
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
} else {
- mavlink_log_info(mavlink_fd, "accel calibration: failed");
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
}
return res;
@@ -266,13 +268,16 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
done_count = 0;
for (int i = 0; i < 6; i++) {
- if (!data_collected[i]) {
+ if (data_collected[i]) {
+ done_count++;
+
+ } else {
done = false;
}
}
if (old_done_count != done_count)
- mavlink_log_info(mavlink_fd, "accel calibration: progress <%u>", 17 * done_count);
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 17 * done_count);
if (done)
break;
@@ -293,7 +298,7 @@ int do_accel_calibration_measurements(int mavlink_fd, float accel_offs[3], float
}
if (data_collected[orient]) {
- mavlink_log_info(mavlink_fd, "%s done, please rotate to a different axis", orientation_strs[orient]);
+ mavlink_log_info(mavlink_fd, "%s done, rotate to a different axis", orientation_strs[orient]);
continue;
}
@@ -374,6 +379,9 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
d = d * d;
accel_disp[i] = accel_disp[i] * (1.0f - w);
+ if (d > still_thr2 * 8.0f)
+ d = still_thr2 * 8.0f;
+
if (d > accel_disp[i])
accel_disp[i] = d;
}
@@ -397,12 +405,12 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
}
}
- } else if (accel_disp[0] > still_thr2 * 2.0f ||
- accel_disp[1] > still_thr2 * 2.0f ||
- accel_disp[2] > still_thr2 * 2.0f) {
+ } else if (accel_disp[0] > still_thr2 * 4.0f ||
+ accel_disp[1] > still_thr2 * 4.0f ||
+ accel_disp[2] > still_thr2 * 4.0f) {
/* not still, reset still start time */
if (t_still != 0) {
- mavlink_log_info(mavlink_fd, "detected motion, please hold still...");
+ mavlink_log_info(mavlink_fd, "detected motion, hold still...");
t_still = 0;
}
}
@@ -416,7 +424,7 @@ int detect_orientation(int mavlink_fd, int sub_sensor_combined)
}
if (poll_errcount > 1000) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed reading sensor");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
return ERROR;
}
}
diff --git a/src/modules/commander/calibration_messages.h b/src/modules/commander/calibration_messages.h
new file mode 100644
index 000000000..fd8b8564d
--- /dev/null
+++ b/src/modules/commander/calibration_messages.h
@@ -0,0 +1,57 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ * Author: Anton Babushkin <anton.babushkin@me.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name PX4 nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/**
+ * @file calibration_messages.h
+ *
+ * Common calibration messages.
+ *
+ * @author Anton Babushkin <anton.babushkin@me.com>
+ */
+
+#ifndef CALIBRATION_MESSAGES_H_
+#define CALIBRATION_MESSAGES_H_
+
+#define CAL_STARTED_MSG "%s calibration: started"
+#define CAL_DONE_MSG "%s calibration: done"
+#define CAL_FAILED_MSG "%s calibration: failed"
+#define CAL_PROGRESS_MSG "%s calibration: progress <%u>"
+
+#define CAL_FAILED_SENSOR_MSG "ERROR: failed reading sensor"
+#define CAL_FAILED_RESET_CAL_MSG "ERROR: failed to reset calibration"
+#define CAL_FAILED_APPLY_CAL_MSG "ERROR: failed to apply calibration"
+#define CAL_FAILED_SET_PARAMS_MSG "ERROR: failed to set parameters"
+#define CAL_FAILED_SAVE_PARAMS_MSG "ERROR: failed to save parameters"
+
+#endif /* CALIBRATION_MESSAGES_H_ */
diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp
index 219ae6cb2..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,9 +58,12 @@
#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: started");
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "don't move system");
struct gyro_scale gyro_scale = {
0.0f,
@@ -77,19 +82,19 @@ int do_gyro_calibration(int mavlink_fd)
close(fd);
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to reset scale / offsets");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
}
- /* subscribe to gyro sensor topic */
- int sub_sensor_gyro = orb_subscribe(ORB_ID(sensor_gyro));
- struct gyro_report gyro_report;
-
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];
@@ -106,19 +111,21 @@ int do_gyro_calibration(int mavlink_fd)
calibration_counter++;
if (calibration_counter % (calibration_count / 20) == 0)
- mavlink_log_info(mavlink_fd, "gyro calibration: progress <%u>", (calibration_counter * 100) / calibration_count);
+ 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, "ERROR: failed reading gyro sensor");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
res = ERROR;
break;
}
}
+ close(sub_sensor_gyro);
+
gyro_scale.x_offset /= calibration_count;
gyro_scale.y_offset /= calibration_count;
gyro_scale.z_offset /= calibration_count;
@@ -137,7 +144,7 @@ int do_gyro_calibration(int mavlink_fd)
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");
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set offset params");
res = ERROR;
}
}
@@ -257,14 +264,12 @@ int do_gyro_calibration(int mavlink_fd)
#endif
- close(sub_sensor_gyro);
-
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");
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to set scale params");
res = ERROR;
}
}
@@ -276,7 +281,7 @@ int do_gyro_calibration(int mavlink_fd)
close(fd);
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to apply new params for gyro");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
}
}
@@ -285,15 +290,15 @@ int do_gyro_calibration(int mavlink_fd)
res = param_save_default();
if (res != OK) {
- mavlink_log_critical(mavlink_fd, "ERROR: failed to save parameters");
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
}
}
if (res == OK) {
- mavlink_log_info(mavlink_fd, "gyro calibration: done");
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
} else {
- mavlink_log_info(mavlink_fd, "gyro calibration: failed");
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
}
return res;
diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp
index b0d4266be..09f4104f8 100644
--- a/src/modules/commander/mag_calibration.cpp
+++ b/src/modules/commander/mag_calibration.cpp
@@ -33,12 +33,14 @@
/**
* @file mag_calibration.cpp
+ *
* Magnetometer calibration routine
*/
#include "mag_calibration.h"
#include "commander_helper.h"
#include "calibration_routines.h"
+#include "calibration_messages.h"
#include <stdio.h>
#include <stdlib.h>
@@ -59,26 +61,20 @@
#endif
static const int ERROR = -1;
+static const char *sensor_name = "mag";
+
int do_mag_calibration(int mavlink_fd)
{
- mavlink_log_info(mavlink_fd, "please put the system in a rest position and wait.");
-
- int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
- struct mag_report mag;
+ mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
+ mavlink_log_info(mavlink_fd, "don't move system");
/* 45 seconds */
uint64_t calibration_interval = 45 * 1000 * 1000;
- /* maximum 2000 values */
+ /* maximum 500 values */
const unsigned int calibration_maxcount = 500;
unsigned int calibration_counter = 0;
- /* limit update rate to get equally spaced measurements over time (in ms) */
- orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
-
- int fd = open(MAG_DEVICE_PATH, O_RDONLY);
-
- /* erase old calibration */
struct mag_scale mscale_null = {
0.0f,
1.0f,
@@ -88,97 +84,92 @@ int do_mag_calibration(int mavlink_fd)
1.0f,
};
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null)) {
- warn("WARNING: failed to set scale / offsets for mag");
- mavlink_log_info(mavlink_fd, "failed to set scale / offsets for mag");
- }
+ int res = OK;
- /* calibrate range */
- if (OK != ioctl(fd, MAGIOCCALIBRATE, fd)) {
- warnx("failed to calibrate scale");
- }
+ /* erase old calibration */
+ int fd = open(MAG_DEVICE_PATH, O_RDONLY);
+ res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null);
- close(fd);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
+ }
- mavlink_log_info(mavlink_fd, "mag cal progress <20> percent");
+ if (res == OK) {
+ /* calibrate range */
+ res = ioctl(fd, MAGIOCCALIBRATE, fd);
- /* calibrate offsets */
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to calibrate scale");
+ }
+ }
- // uint64_t calibration_start = hrt_absolute_time();
+ close(fd);
- uint64_t axis_deadline = hrt_absolute_time();
- uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
+ float *x;
+ float *y;
+ float *z;
- const char axislabels[3] = { 'X', 'Y', 'Z'};
- int axis_index = -1;
+ if (res == OK) {
+ /* allocate memory */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20);
- float *x = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *y = (float *)malloc(sizeof(float) * calibration_maxcount);
- float *z = (float *)malloc(sizeof(float) * calibration_maxcount);
+ x = (float *)malloc(sizeof(float) * calibration_maxcount);
+ y = (float *)malloc(sizeof(float) * calibration_maxcount);
+ z = (float *)malloc(sizeof(float) * calibration_maxcount);
- if (x == NULL || y == NULL || z == NULL) {
- warnx("mag cal failed: out of memory");
- mavlink_log_info(mavlink_fd, "mag cal failed: out of memory");
- warnx("x:%p y:%p z:%p\n", x, y, z);
- return ERROR;
+ if (x == NULL || y == NULL || z == NULL) {
+ mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
+ res = ERROR;
+ }
}
- mavlink_log_info(mavlink_fd, "scale calibration completed, dynamic calibration starting..");
+ if (res == OK) {
+ int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
+ struct mag_report mag;
- unsigned poll_errcount = 0;
+ /* limit update rate to get equally spaced measurements over time (in ms) */
+ orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
- while (hrt_absolute_time() < calibration_deadline &&
- calibration_counter < calibration_maxcount) {
+ /* calibrate offsets */
+ uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
+ unsigned poll_errcount = 0;
- /* wait blocking for new data */
- struct pollfd fds[1];
- fds[0].fd = sub_mag;
- fds[0].events = POLLIN;
+ mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis");
- /* user guidance */
- if (hrt_absolute_time() >= axis_deadline &&
- axis_index < 3) {
+ while (hrt_absolute_time() < calibration_deadline &&
+ calibration_counter < calibration_maxcount) {
- axis_index++;
+ /* wait blocking for new data */
+ struct pollfd fds[1];
+ fds[0].fd = sub_mag;
+ fds[0].events = POLLIN;
- mavlink_log_info(mavlink_fd, "please rotate in a figure 8 or around %c axis.", axislabels[axis_index]);
- tune_neutral();
+ int poll_ret = poll(fds, 1, 1000);
- axis_deadline += calibration_interval / 3;
- }
+ if (poll_ret > 0) {
+ orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
- if (!(axis_index < 3)) {
- break;
- }
-
- int poll_ret = poll(fds, 1, 1000);
-
- if (poll_ret > 0) {
- orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
+ x[calibration_counter] = mag.x;
+ y[calibration_counter] = mag.y;
+ z[calibration_counter] = mag.z;
- x[calibration_counter] = mag.x;
- y[calibration_counter] = mag.y;
- z[calibration_counter] = mag.z;
+ calibration_counter++;
- calibration_counter++;
- if (calibration_counter % (calibration_maxcount / 20) == 0)
- mavlink_log_info(mavlink_fd, "mag cal progress <%u> percent", 20 + (calibration_counter * 50) / calibration_maxcount);
+ if (calibration_counter % (calibration_maxcount / 20) == 0)
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
+ } else {
+ poll_errcount++;
+ }
- } else {
- poll_errcount++;
- }
-
- if (poll_errcount > 1000) {
- mavlink_log_info(mavlink_fd, "ERROR: Failed reading mag sensor");
- close(sub_mag);
- free(x);
- free(y);
- free(z);
- return ERROR;
+ if (poll_errcount > 1000) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
+ res = ERROR;
+ break;
+ }
}
-
+ close(sub_mag);
}
float sphere_x;
@@ -186,93 +177,100 @@ int do_mag_calibration(int mavlink_fd)
float sphere_z;
float sphere_radius;
- mavlink_log_info(mavlink_fd, "mag cal progress <70> percent");
- sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
- mavlink_log_info(mavlink_fd, "mag cal progress <80> percent");
+ if (res == OK) {
+ /* sphere fit */
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 70);
+ sphere_fit_least_squares(x, y, z, calibration_counter, 100, 0.0f, &sphere_x, &sphere_y, &sphere_z, &sphere_radius);
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 80);
- free(x);
- free(y);
- free(z);
+ if (!isfinite(sphere_x) || !isfinite(sphere_y) || !isfinite(sphere_z)) {
+ mavlink_log_critical(mavlink_fd, "ERROR: NaN in sphere fit");
+ res = ERROR;
+ }
+ }
- if (isfinite(sphere_x) && isfinite(sphere_y) && isfinite(sphere_z)) {
+ if (x != NULL)
+ free(x);
- fd = open(MAG_DEVICE_PATH, 0);
+ if (y != NULL)
+ free(y);
- struct mag_scale mscale;
+ if (z != NULL)
+ free(z);
- if (OK != ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to get scale / offsets for mag");
+ if (res == OK) {
+ /* apply calibration and set parameters */
+ struct mag_scale mscale;
- mscale.x_offset = sphere_x;
- mscale.y_offset = sphere_y;
- mscale.z_offset = sphere_z;
+ fd = open(MAG_DEVICE_PATH, 0);
+ res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale);
- if (OK != ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale))
- warn("WARNING: failed to set scale / offsets for mag");
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, "ERROR: failed to get current calibration");
+ }
- close(fd);
+ if (res == OK) {
+ mscale.x_offset = sphere_x;
+ mscale.y_offset = sphere_y;
+ mscale.z_offset = sphere_z;
- /* announce and set new offset */
+ res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale);
- if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset))) {
- warnx("Setting X mag offset failed!\n");
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
+ }
}
- if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset))) {
- warnx("Setting Y mag offset failed!\n");
- }
+ close(fd);
- if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset))) {
- warnx("Setting Z mag offset failed!\n");
- }
+ if (res == OK) {
+ /* set parameters */
+ if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
+ res = ERROR;
- if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale))) {
- warnx("Setting X mag scale failed!\n");
- }
+ if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
+ res = ERROR;
- if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale))) {
- warnx("Setting Y mag scale failed!\n");
- }
+ if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
+ res = ERROR;
- if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale))) {
- warnx("Setting Z mag scale failed!\n");
- }
+ if (param_set(param_find("SENS_MAG_XSCALE"), &(mscale.x_scale)))
+ res = ERROR;
+
+ if (param_set(param_find("SENS_MAG_YSCALE"), &(mscale.y_scale)))
+ res = ERROR;
- mavlink_log_info(mavlink_fd, "mag cal progress <90> percent");
+ if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
+ res = ERROR;
- /* auto-save to EEPROM */
- int save_ret = param_save_default();
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
+ }
- if (save_ret != 0) {
- warn("WARNING: auto-save of params to storage failed");
- mavlink_log_info(mavlink_fd, "FAILED storing calibration");
- close(sub_mag);
- return ERROR;
+ mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 90);
}
- warnx("\tscale: %.6f %.6f %.6f\n \toffset: %.6f %.6f %.6f\nradius: %.6f GA\n",
- (double)mscale.x_scale, (double)mscale.y_scale, (double)mscale.z_scale,
- (double)mscale.x_offset, (double)mscale.y_offset, (double)mscale.z_offset, (double)sphere_radius);
+ if (res == OK) {
+ /* auto-save to EEPROM */
+ res = param_save_default();
- char buf[52];
- sprintf(buf, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
- (double)mscale.y_offset, (double)mscale.z_offset);
- mavlink_log_info(mavlink_fd, buf);
+ if (res != OK) {
+ mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
+ }
+ }
- sprintf(buf, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
- (double)mscale.y_scale, (double)mscale.z_scale);
- mavlink_log_info(mavlink_fd, buf);
+ mavlink_log_info(mavlink_fd, "mag off: x:%.2f y:%.2f z:%.2f Ga", (double)mscale.x_offset,
+ (double)mscale.y_offset, (double)mscale.z_offset);
+ mavlink_log_info(mavlink_fd, "mag scale: x:%.2f y:%.2f z:%.2f", (double)mscale.x_scale,
+ (double)mscale.y_scale, (double)mscale.z_scale);
- mavlink_log_info(mavlink_fd, "magnetometer calibration completed");
- mavlink_log_info(mavlink_fd, "mag cal progress <100> percent");
+ if (res == OK) {
+ mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
- close(sub_mag);
- return OK;
- /* third beep by cal end routine */
+ } else {
+ mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
+ }
- } else {
- mavlink_log_info(mavlink_fd, "mag calibration FAILED (NaN in sphere fit)");
- close(sub_mag);
- return ERROR;
+ return res;
}
}