PX4 Firmware
PX4 Autopilot Software http://px4.io
PX4Magnetometer.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018 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 #include "PX4Magnetometer.hpp"
36 
38 
39 PX4Magnetometer::PX4Magnetometer(uint32_t device_id, uint8_t priority, enum Rotation rotation) :
40  CDev(nullptr),
41  _sensor_mag_pub{ORB_ID(sensor_mag), priority},
42  _rotation{rotation}
43 {
45 
47  _sensor_mag_pub.get().scaling = 1.0f;
48 }
49 
51 {
52  if (_class_device_instance != -1) {
54  }
55 }
56 
57 int
58 PX4Magnetometer::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
59 {
60  switch (cmd) {
61  case MAGIOCSSCALE: {
62  // Copy offsets and scale factors in
63  mag_calibration_s cal{};
64  memcpy(&cal, (mag_calibration_s *) arg, sizeof(cal));
65 
66  _calibration_offset = matrix::Vector3f{cal.x_offset, cal.y_offset, cal.z_offset};
67  _calibration_scale = matrix::Vector3f{cal.x_scale, cal.y_scale, cal.z_scale};
68  }
69 
70  return PX4_OK;
71 
72  case MAGIOCGSCALE: {
73  // copy out scale factors
74  mag_calibration_s cal{};
76  cal.y_offset = _calibration_offset(1);
77  cal.z_offset = _calibration_offset(2);
78  cal.x_scale = _calibration_scale(0);
79  cal.y_scale = _calibration_scale(1);
80  cal.z_scale = _calibration_scale(2);
81  memcpy((mag_calibration_s *)arg, &cal, sizeof(cal));
82  }
83 
84  return 0;
85 
86  case DEVIOCGDEVICEID:
87  return _sensor_mag_pub.get().device_id;
88 
89  default:
90  return -ENOTTY;
91  }
92 }
93 
94 void
96 {
97  // current DeviceStructure
98  union device::Device::DeviceId device_id;
99  device_id.devid = _sensor_mag_pub.get().device_id;
100 
101  // update to new device type
102  device_id.devid_s.devtype = devtype;
103 
104  // copy back to report
105  _sensor_mag_pub.get().device_id = device_id.devid;
106 }
107 
108 void
109 PX4Magnetometer::update(hrt_abstime timestamp, int16_t x, int16_t y, int16_t z)
110 {
111  sensor_mag_s &report = _sensor_mag_pub.get();
112  report.timestamp = timestamp;
113 
114  // Apply rotation (before scaling)
115  float xraw_f = x;
116  float yraw_f = y;
117  float zraw_f = z;
118  rotate_3f(_rotation, xraw_f, yraw_f, zraw_f);
119 
120  const matrix::Vector3f raw_f{xraw_f, yraw_f, zraw_f};
121 
122  // Apply range scale and the calibrating offset/scale
123  const matrix::Vector3f val_calibrated{(((raw_f.emult(_sensitivity) * report.scaling) - _calibration_offset).emult(_calibration_scale))};
124 
125  // Raw values (ADC units 0 - 65535)
126  report.x_raw = x;
127  report.y_raw = y;
128  report.z_raw = z;
129 
130  report.x = val_calibrated(0);
131  report.y = val_calibrated(1);
132  report.z = val_calibrated(2);
133 
134  poll_notify(POLLIN);
136 }
137 
138 void
140 {
141  PX4_INFO(MAG_BASE_DEVICE_PATH " device instance: %d", _class_device_instance);
142 
143  PX4_INFO("calibration scale: %.5f %.5f %.5f", (double)_calibration_scale(0), (double)_calibration_scale(1),
144  (double)_calibration_scale(2));
145  PX4_INFO("calibration offset: %.5f %.5f %.5f", (double)_calibration_offset(0), (double)_calibration_offset(1),
146  (double)_calibration_offset(2));
147 
148  print_message(_sensor_mag_pub.get());
149 }
#define MAGIOCGSCALE
copy the mag scaling constants to the structure pointed to by (arg)
Definition: drv_mag.h:76
void set_device_type(uint8_t devtype)
virtual int register_class_devname(const char *class_devname)
Register a class device name, automatically adding device class instance suffix if need be...
Definition: CDev.cpp:78
__EXPORT void rotate_3f(enum Rotation rot, float &x, float &y, float &z)
rotate a 3 element float vector in-place
Definition: rotation.cpp:63
mag scaling factors; Vout = (Vin * Vscale) + Voffset
Definition: drv_mag.h:56
matrix::Vector3f _calibration_scale
float scaling
Definition: sensor_mag.h:60
static int32_t device_id[max_accel_sens]
struct DeviceStructure devid_s
Definition: Device.hpp:157
virtual void poll_notify(pollevent_t events)
Report new poll events.
Definition: CDev.cpp:330
float x_offset
Definition: drv_mag.h:57
Definitions for the generic base classes in the device framework.
uORB::PublicationMultiData< sensor_mag_s > _sensor_mag_pub
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
#define MAGIOCSSCALE
set the mag scaling constants to the structure pointed to by (arg)
Definition: drv_mag.h:73
#define MAG_BASE_DEVICE_PATH
Definition: drv_mag.h:47
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance)
Register a class device name, automatically adding device class instance suffix if need be...
Definition: CDev.cpp:109
void update(hrt_abstime timestamp, int16_t x, int16_t y, int16_t z)
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
matrix::Vector3f _sensitivity
matrix::Vector3f _calibration_offset
enum Rotation _rotation
int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override
Perform an ioctl operation on the device.
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
~PX4Magnetometer() override
uint64_t timestamp
Definition: sensor_mag.h:53
uint32_t device_id
Definition: sensor_mag.h:55
int16_t z_raw
Definition: sensor_mag.h:63
int16_t x_raw
Definition: sensor_mag.h:61
int16_t y_raw
Definition: sensor_mag.h:62
PX4Magnetometer(uint32_t device_id, uint8_t priority, enum Rotation rotation)