mag_calibration.cpp 7.4 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
/****************************************************************************
 *
 *   Copyright (C) 2013 PX4 Development Team. All rights reserved.
 *
 * 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.
 *
 ****************************************************************************/

/**
35
 * @file mag_calibration.cpp
36
 *
37
38
39
40
41
42
 * Magnetometer calibration routine
 */

#include "mag_calibration.h"
#include "commander_helper.h"
#include "calibration_routines.h"
43
#include "calibration_messages.h"
44
45
46
47
48
49
50
51
52
53
54
55
56
57

#include <stdio.h>
#include <stdlib.h>
#include <string.h>
#include <poll.h>
#include <math.h>
#include <fcntl.h>
#include <drivers/drv_hrt.h>
#include <uORB/topics/sensor_combined.h>
#include <drivers/drv_mag.h>
#include <mavlink/mavlink_log.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>

58
59
60
61
62
/* oddly, ERROR is not defined for c++ */
#ifdef ERROR
# undef ERROR
#endif
static const int ERROR = -1;
63

64
65
static const char *sensor_name = "mag";

66
int do_mag_calibration(int mavlink_fd)
67
{
68
69
	mavlink_log_info(mavlink_fd, CAL_STARTED_MSG, sensor_name);
	mavlink_log_info(mavlink_fd, "don't move system");
70
71
72
73

	/* 45 seconds */
	uint64_t calibration_interval = 45 * 1000 * 1000;

74
	/* maximum 500 values */
75
76
77
78
79
80
81
82
83
84
85
86
	const unsigned int calibration_maxcount = 500;
	unsigned int calibration_counter = 0;

	struct mag_scale mscale_null = {
		0.0f,
		1.0f,
		0.0f,
		1.0f,
		0.0f,
		1.0f,
	};

87
	int res = OK;
88

89
90
91
	/* erase old calibration */
	int fd = open(MAG_DEVICE_PATH, O_RDONLY);
	res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale_null);
92

93
94
95
	if (res != OK) {
		mavlink_log_critical(mavlink_fd, CAL_FAILED_RESET_CAL_MSG);
	}
96

97
98
99
	if (res == OK) {
		/* calibrate range */
		res = ioctl(fd, MAGIOCCALIBRATE, fd);
100

101
102
103
104
		if (res != OK) {
			mavlink_log_critical(mavlink_fd, "ERROR: failed to calibrate scale");
		}
	}
105

106
	close(fd);
107

108
109
110
	float *x;
	float *y;
	float *z;
111

112
113
114
	if (res == OK) {
		/* allocate memory */
		mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20);
115

116
117
118
		x = (float *)malloc(sizeof(float) * calibration_maxcount);
		y = (float *)malloc(sizeof(float) * calibration_maxcount);
		z = (float *)malloc(sizeof(float) * calibration_maxcount);
119

120
121
122
123
		if (x == NULL || y == NULL || z == NULL) {
			mavlink_log_critical(mavlink_fd, "ERROR: out of memory");
			res = ERROR;
		}
124
125
	}

126
127
128
	if (res == OK) {
		int sub_mag = orb_subscribe(ORB_ID(sensor_mag));
		struct mag_report mag;
Lorenz Meier's avatar
Lorenz Meier committed
129

130
131
		/* limit update rate to get equally spaced measurements over time (in ms) */
		orb_set_interval(sub_mag, (calibration_interval / 1000) / calibration_maxcount);
Lorenz Meier's avatar
Lorenz Meier committed
132

133
134
135
		/* calibrate offsets */
		uint64_t calibration_deadline = hrt_absolute_time() + calibration_interval;
		unsigned poll_errcount = 0;
136

137
		mavlink_log_info(mavlink_fd, "rotate in a figure 8 around all axis");
138

139
140
		while (hrt_absolute_time() < calibration_deadline &&
		       calibration_counter < calibration_maxcount) {
141

142
143
144
145
			/* wait blocking for new data */
			struct pollfd fds[1];
			fds[0].fd = sub_mag;
			fds[0].events = POLLIN;
146

147
			int poll_ret = poll(fds, 1, 1000);
148

149
150
			if (poll_ret > 0) {
				orb_copy(ORB_ID(sensor_mag), sub_mag, &mag);
151

152
153
154
				x[calibration_counter] = mag.x;
				y[calibration_counter] = mag.y;
				z[calibration_counter] = mag.z;
155

156
				calibration_counter++;
157

158
159
				if (calibration_counter % (calibration_maxcount / 20) == 0)
					mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 20 + (calibration_counter * 50) / calibration_maxcount);
160

161
162
163
			} else {
				poll_errcount++;
			}
164

165
166
167
168
169
			if (poll_errcount > 1000) {
				mavlink_log_critical(mavlink_fd, CAL_FAILED_SENSOR_MSG);
				res = ERROR;
				break;
			}
170
		}
Lorenz Meier's avatar
Lorenz Meier committed
171

172
		close(sub_mag);
173
174
175
176
177
178
179
	}

	float sphere_x;
	float sphere_y;
	float sphere_z;
	float sphere_radius;

180
181
182
183
184
	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);
185

186
187
188
189
190
		if (!isfinite(sphere_x) || !isfinite(sphere_y) || !isfinite(sphere_z)) {
			mavlink_log_critical(mavlink_fd, "ERROR: NaN in sphere fit");
			res = ERROR;
		}
	}
191

192
193
	if (x != NULL)
		free(x);
194

195
196
	if (y != NULL)
		free(y);
197

198
199
	if (z != NULL)
		free(z);
200

201
202
203
	if (res == OK) {
		/* apply calibration and set parameters */
		struct mag_scale mscale;
204

205
206
		fd = open(MAG_DEVICE_PATH, 0);
		res = ioctl(fd, MAGIOCGSCALE, (long unsigned int)&mscale);
207

208
209
210
		if (res != OK) {
			mavlink_log_critical(mavlink_fd, "ERROR: failed to get current calibration");
		}
211

212
213
214
215
		if (res == OK) {
			mscale.x_offset = sphere_x;
			mscale.y_offset = sphere_y;
			mscale.z_offset = sphere_z;
216

217
			res = ioctl(fd, MAGIOCSSCALE, (long unsigned int)&mscale);
218

219
220
221
			if (res != OK) {
				mavlink_log_critical(mavlink_fd, CAL_FAILED_APPLY_CAL_MSG);
			}
222
223
		}

224
		close(fd);
225

226
227
228
229
		if (res == OK) {
			/* set parameters */
			if (param_set(param_find("SENS_MAG_XOFF"), &(mscale.x_offset)))
				res = ERROR;
230

231
232
			if (param_set(param_find("SENS_MAG_YOFF"), &(mscale.y_offset)))
				res = ERROR;
233

234
235
			if (param_set(param_find("SENS_MAG_ZOFF"), &(mscale.z_offset)))
				res = ERROR;
236

237
238
239
240
241
			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;
242

243
244
			if (param_set(param_find("SENS_MAG_ZSCALE"), &(mscale.z_scale)))
				res = ERROR;
245

246
247
248
			if (res != OK) {
				mavlink_log_critical(mavlink_fd, CAL_FAILED_SET_PARAMS_MSG);
			}
249

250
			mavlink_log_info(mavlink_fd, CAL_PROGRESS_MSG, sensor_name, 90);
251
252
		}

253
254
255
		if (res == OK) {
			/* auto-save to EEPROM */
			res = param_save_default();
256

257
258
259
260
			if (res != OK) {
				mavlink_log_critical(mavlink_fd, CAL_FAILED_SAVE_PARAMS_MSG);
			}
		}
261

262
263
264
265
		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);
266

267
268
		if (res == OK) {
			mavlink_log_info(mavlink_fd, CAL_DONE_MSG, sensor_name);
269

270
271
272
		} else {
			mavlink_log_info(mavlink_fd, CAL_FAILED_MSG, sensor_name);
		}
273

274
		return res;
275
	}
276
}