PX4 Firmware
PX4 Autopilot Software http://px4.io
df_ak8963_wrapper.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2016 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file df_ak8963_wrapper.cpp
36  * Lightweight driver to access the AK8963 of the DriverFramework.
37  */
38 
39 #include <px4_platform_common/px4_config.h>
40 
41 #include <sys/types.h>
42 #include <sys/stat.h>
43 #include <stdint.h>
44 #include <stddef.h>
45 #include <stdlib.h>
46 #include <string.h>
47 #include <math.h>
48 #include <unistd.h>
49 #include <px4_platform_common/getopt.h>
50 #include <errno.h>
51 #include <lib/parameters/param.h>
52 #include <perf/perf_counter.h>
53 #include <systemlib/err.h>
54 
55 #include <drivers/drv_mag.h>
56 #include <drivers/drv_hrt.h>
57 
59 
60 #include <board_config.h>
61 
63 
64 #include <ak8963/AK8963.hpp>
65 #include <DevMgr.hpp>
66 
67 
68 extern "C" { __EXPORT int df_ak8963_wrapper_main(int argc, char *argv[]); }
69 
70 using namespace DriverFramework;
71 
72 
73 class DfAK8963Wrapper : public AK8963
74 {
75 public:
76  DfAK8963Wrapper(enum Rotation rotation);
77  ~DfAK8963Wrapper();
78 
79 
80  /**
81  * Start automatic measurement.
82  *
83  * @return 0 on success
84  */
85  int start();
86 
87  /**
88  * Stop automatic measurement.
89  *
90  * @return 0 on success
91  */
92  int stop();
93 
94  void print_calibration();
95 
96 private:
97  int _publish(struct mag_sensor_data &data);
98 
99  void _update_mag_calibration();
100 
102 
104 
106  float x_offset;
107  float x_scale;
108  float y_offset;
109  float y_scale;
110  float z_offset;
111  float z_scale;
112  } _mag_calibration;
113 
115 
117 
119 
120 };
121 
123  AK8963(MAG_DEVICE_PATH),
124  _mag_topic(nullptr),
125  _param_update_sub(-1),
126  _mag_calibration{},
128  _mag_sample_perf(perf_alloc(PC_ELAPSED, "df_mag_read"))
129 {
130  // Set sane default calibration values
131  _mag_calibration.x_scale = 1.0f;
132  _mag_calibration.y_scale = 1.0f;
133  _mag_calibration.z_scale = 1.0f;
134  _mag_calibration.x_offset = 0.0f;
135  _mag_calibration.y_offset = 0.0f;
136  _mag_calibration.z_offset = 0.0f;
137 
138  // Get sensor rotation matrix
139  _rotation_matrix = get_rot_matrix(rotation);
140 }
141 
143 {
145 }
146 
148 {
149  /* Subscribe to param update topic. */
150  if (_param_update_sub < 0) {
151  _param_update_sub = orb_subscribe(ORB_ID(parameter_update));
152  }
153 
154  /* Init device and start sensor. */
155  int ret = init();
156 
157  if (ret != 0) {
158  PX4_ERR("AK8963 init fail: %d", ret);
159  return ret;
160  }
161 
162  ret = AK8963::start();
163 
164  if (ret != 0) {
165  PX4_ERR("AK8963 start fail: %d", ret);
166  return ret;
167  }
168 
169  /* Force getting the calibration values. */
171 
172  return 0;
173 }
174 
176 {
177  /* Stop sensor. */
178  int ret = AK8963::stop();
179 
180  if (ret != 0) {
181  PX4_ERR("AK8963 stop fail: %d", ret);
182  return ret;
183  }
184 
185  return 0;
186 }
187 
189 {
190  // TODO: replace magic number
191  for (unsigned i = 0; i < 3; ++i) {
192 
193  // TODO: remove printfs and add error counter
194 
195  char str[30];
196  (void)sprintf(str, "CAL_MAG%u_ID", i);
197  int32_t device_id;
198  int res = param_get(param_find(str), &device_id);
199 
200  if (res != OK) {
201  PX4_ERR("Could not access param %s", str);
202  continue;
203  }
204 
205  if ((uint32_t)device_id != m_id.dev_id) {
206  continue;
207  }
208 
209  (void)sprintf(str, "CAL_MAG%u_XSCALE", i);
211 
212  if (res != OK) {
213  PX4_ERR("Could not access param %s", str);
214  }
215 
216  (void)sprintf(str, "CAL_MAG%u_YSCALE", i);
218 
219  if (res != OK) {
220  PX4_ERR("Could not access param %s", str);
221  }
222 
223  (void)sprintf(str, "CAL_MAG%u_ZSCALE", i);
225 
226  if (res != OK) {
227  PX4_ERR("Could not access param %s", str);
228  }
229 
230  (void)sprintf(str, "CAL_MAG%u_XOFF", i);
232 
233  if (res != OK) {
234  PX4_ERR("Could not access param %s", str);
235  }
236 
237  (void)sprintf(str, "CAL_MAG%u_YOFF", i);
239 
240  if (res != OK) {
241  PX4_ERR("Could not access param %s", str);
242  }
243 
244  (void)sprintf(str, "CAL_MAG%u_ZOFF", i);
246 
247  if (res != OK) {
248  PX4_ERR("Could not access param %s", str);
249  }
250  }
251 }
252 
254 {
255  PX4_INFO("calibration x_offset: %f", (double)_mag_calibration.x_offset);
256  PX4_INFO("calibration x_scale: %f", (double)_mag_calibration.x_scale);
257  PX4_INFO("calibration y_offset: %f", (double)_mag_calibration.y_offset);
258  PX4_INFO("calibration y_scale: %f", (double)_mag_calibration.y_scale);
259  PX4_INFO("calibration z_offset: %f", (double)_mag_calibration.z_offset);
260  PX4_INFO("calibration z_scale: %f", (double)_mag_calibration.z_scale);
261 }
262 
263 int DfAK8963Wrapper::_publish(struct mag_sensor_data &data)
264 {
265  /* Check if calibration values are still up-to-date. */
266  bool updated;
267  orb_check(_param_update_sub, &updated);
268 
269  if (updated) {
270  parameter_update_s parameter_update;
271  orb_copy(ORB_ID(parameter_update), _param_update_sub, &parameter_update);
272 
274  }
275 
276  /* Publish mag first. */
278 
279  mag_report mag_report = {};
280  mag_report.timestamp = hrt_absolute_time();
281  mag_report.is_external = true;
282 
283  // TODO: remove these (or get the values)
284  mag_report.x_raw = 0;
285  mag_report.y_raw = 0;
286  mag_report.z_raw = 0;
287 
288  matrix::Vector3f mag_val(data.field_x_ga, data.field_y_ga, data.field_z_ga);
289 
290  // apply sensor rotation on the accel measurement
291  mag_val = _rotation_matrix * mag_val;
292 
293  mag_report.x = (mag_val(0) - _mag_calibration.x_offset) * _mag_calibration.x_scale;
294  mag_report.y = (mag_val(1) - _mag_calibration.y_offset) * _mag_calibration.y_scale;
295  mag_report.z = (mag_val(2) - _mag_calibration.z_offset) * _mag_calibration.z_scale;
296 
297 
298  // TODO: get these right
299  //mag_report.scaling = -1.0f;
300 
301  mag_report.device_id = m_id.dev_id;
302 
303  // TODO: when is this ever blocked?
304  if (!(m_pub_blocked)) {
305 
306  if (_mag_topic == nullptr) {
307  _mag_topic = orb_advertise_multi(ORB_ID(sensor_mag), &mag_report,
309 
310  } else {
311  orb_publish(ORB_ID(sensor_mag), _mag_topic, &mag_report);
312  }
313 
314  }
315 
317 
318  return 0;
319 };
320 
321 
323 {
324 
326 
327 int start(enum Rotation rotation);
328 int stop();
329 int info();
330 void usage();
331 
332 int start(enum Rotation rotation)
333 {
334  g_dev = new DfAK8963Wrapper(rotation);
335 
336  if (g_dev == nullptr) {
337  PX4_ERR("failed instantiating DfAK8963Wrapper object");
338  return -1;
339  }
340 
341  int ret = g_dev->start();
342 
343  if (ret != 0) {
344  PX4_ERR("DfAK8963Wrapper start failed");
345  return ret;
346  }
347 
348  // Open the MAG sensor
349  DevHandle h;
350  DevMgr::getHandle(MAG_DEVICE_PATH, h);
351 
352  if (!h.isValid()) {
353  DF_LOG_INFO("Error: unable to obtain a valid handle for the receiver at: %s (%d)",
354  MAG_DEVICE_PATH, h.getError());
355  return -1;
356  }
357 
358  DevMgr::releaseHandle(h);
359 
360  return 0;
361 }
362 
363 int stop()
364 {
365  if (g_dev == nullptr) {
366  PX4_ERR("driver not running");
367  return 1;
368  }
369 
370  int ret = g_dev->stop();
371 
372  if (ret != 0) {
373  PX4_ERR("driver could not be stopped");
374  return ret;
375  }
376 
377  delete g_dev;
378  g_dev = nullptr;
379  return 0;
380 }
381 
382 /**
383  * Print a little info about the driver.
384  */
385 int
387 {
388  if (g_dev == nullptr) {
389  PX4_ERR("driver not running");
390  return 1;
391  }
392 
393  PX4_DEBUG("state @ %p", g_dev);
394 
395  g_dev->print_calibration();
396 
397  return 0;
398 }
399 
400 void
402 {
403  PX4_INFO("Usage: df_ak8963_wrapper 'start', 'info', 'stop'");
404  PX4_INFO("options:");
405  PX4_INFO(" -R rotation");
406 }
407 
408 } // namespace df_ak8963_wrapper
409 
410 
411 int
412 df_ak8963_wrapper_main(int argc, char *argv[])
413 {
414  int ch;
415  enum Rotation rotation = ROTATION_NONE;
416  int ret = 0;
417  int myoptind = 1;
418  const char *myoptarg = NULL;
419 
420  /* jump over start/off/etc and look at options first */
421  while ((ch = px4_getopt(argc, argv, "R:", &myoptind, &myoptarg)) != EOF) {
422  switch (ch) {
423  case 'R':
424  rotation = (enum Rotation)atoi(myoptarg);
425  break;
426 
427  default:
429  return 0;
430  }
431  }
432 
433  if (argc <= 1) {
435  return 1;
436  }
437 
438  const char *verb = argv[myoptind];
439 
440 
441  if (!strcmp(verb, "start")) {
442  ret = df_ak8963_wrapper::start(rotation);
443  }
444 
445  else if (!strcmp(verb, "stop")) {
446  ret = df_ak8963_wrapper::stop();
447  }
448 
449  else if (!strcmp(verb, "info")) {
450  ret = df_ak8963_wrapper::info();
451  }
452 
453  else {
455  return 1;
456  }
457 
458  return ret;
459 }
DfAK8963Wrapper(enum Rotation rotation)
int orb_copy(const struct orb_metadata *meta, int handle, void *buffer)
Definition: uORB.cpp:90
measure the time elapsed performing an event
Definition: perf_counter.h:56
int start()
Start automatic measurement.
__EXPORT int param_get(param_t param, void *val)
Copy the value of a parameter.
Definition: parameters.cpp:589
struct DfAK8963Wrapper::mag_calibration_s _mag_calibration
void usage(const char *reason)
Print the correct usage.
Definition: Commander.cpp:4238
DfAK8963Wrapper * g_dev
Definition: I2C.hpp:51
int _publish(struct mag_sensor_data &data)
int info()
Print a little info about the driver.
static void stop()
Definition: dataman.cpp:1491
static int32_t device_id[max_accel_sens]
Vector rotation library.
High-resolution timer with callouts and timekeeping.
Global flash based parameter store.
int start(enum Rotation rotation)
int orb_subscribe(const struct orb_metadata *meta)
Definition: uORB.cpp:75
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
Header common to all counters.
void perf_free(perf_counter_t handle)
Free a counter.
orb_advert_t _mag_topic
void init()
Activates/configures the hardware registers.
#define perf_alloc(a, b)
Definition: px4io.h:59
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint8_t * data
Definition: dataman.cpp:149
__EXPORT int df_ak8963_wrapper_main(int argc, char *argv[])
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
void perf_end(perf_counter_t handle)
End a performance event.
matrix::Dcmf _rotation_matrix
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
Definition: uORB.cpp:70
__EXPORT param_t param_find(const char *name)
Look up a parameter by name.
Definition: parameters.cpp:370
static int start()
Definition: dataman.cpp:1452
perf_counter_t _mag_sample_perf
void usage()
Prints info about the driver argument usage.
int orb_check(int handle, bool *updated)
Definition: uORB.cpp:95
__EXPORT matrix::Dcmf get_rot_matrix(enum Rotation rot)
Get the rotation matrix.
Definition: rotation.cpp:45
#define OK
Definition: uavcan_main.cpp:71
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority)
Definition: uORB.cpp:53
void perf_begin(perf_counter_t handle)
Begin a performance event.
int stop()
Stop automatic measurement.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
int stop()
Stop the driver.
Performance measuring tools.
#define mag_report
Definition: drv_mag.h:53