PX4 Firmware
PX4 Autopilot Software http://px4.io
lis3mdl.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2015 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 lis3mdl.h
36  *
37  * Shared defines for the LIS3MDL driver.
38  */
39 
40 #pragma once
41 
42 #include <float.h>
43 
44 #include <drivers/device/i2c.h>
46 #include <drivers/drv_hrt.h>
47 #include <drivers/drv_mag.h>
48 
50 #include <systemlib/err.h>
51 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
52 
53 #include <perf/perf_counter.h>
54 #include <px4_platform_common/defines.h>
55 
56 /**
57  * LIS3MDL internal constants and data structures.
58  */
59 
60 /* Max measurement rate is 80Hz */
61 #define LIS3MDL_CONVERSION_INTERVAL (1000000 / 80) /* 12,500 microseconds */
62 
63 #define NUM_BUS_OPTIONS (sizeof(lis3mdl::bus_options)/sizeof(lis3mdl::bus_options[0]))
64 
65 #define ADDR_WHO_AM_I 0x0f
66 #define ID_WHO_AM_I 0x3d
67 
68 #define ADDR_CTRL_REG1 0x20
69 #define ADDR_CTRL_REG2 0x21
70 #define ADDR_CTRL_REG3 0x22
71 #define ADDR_CTRL_REG4 0x23
72 #define ADDR_CTRL_REG5 0x24
73 
74 #define ADDR_STATUS_REG 0x27
75 #define ADDR_OUT_X_L 0x28
76 #define ADDR_OUT_X_H 0x29
77 #define ADDR_OUT_Y_L 0x2a
78 #define ADDR_OUT_Y_H 0x2b
79 #define ADDR_OUT_Z_L 0x2c
80 #define ADDR_OUT_Z_H 0x2d
81 #define ADDR_OUT_T_L 0x2e
82 #define ADDR_OUT_T_H 0x2f
83 
84 #define MODE_REG_CONTINOUS_MODE (0 << 0)
85 #define MODE_REG_SINGLE_MODE (1 << 0) /* default */
86 
87 #define CNTL_REG1_DEFAULT 0xFC
88 #define CNTL_REG2_DEFAULT 0x00
89 #define CNTL_REG3_DEFAULT 0x00
90 #define CNTL_REG4_DEFAULT 0x0C
91 #define CNTL_REG5_DEFAULT 0x00
92 
93 /* interface factories */
94 extern device::Device *LIS3MDL_SPI_interface(int bus);
95 extern device::Device *LIS3MDL_I2C_interface(int bus);
96 typedef device::Device *(*LIS3MDL_constructor)(int);
97 
103 };
104 
108 };
109 
110 
111 class LIS3MDL : public device::CDev, public px4::ScheduledWorkItem
112 {
113 public:
114  LIS3MDL(device::Device *interface, const char *path, enum Rotation rotation);
115 
116  virtual ~LIS3MDL();
117 
118  virtual int init();
119 
120  virtual int ioctl(struct file *file_pointer, int cmd, unsigned long arg);
121 
122  virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len);
123 
124  /**
125  * Diagnostics - print some basic information about the driver.
126  */
127  void print_info();
128 
129  /**
130  * Configures the device with default register values.
131  */
133 
134  /**
135  * Stop the automatic measurement state machine.
136  */
137  void stop();
138 
139 protected:
141 
142 private:
143 
144  ringbuffer::RingBuffer *_reports;
145 
147 
148  struct mag_report _last_report {}; /**< used for info() */
149 
151 
156 
157  /* status reporting */
158  bool _calibrated; /**< the calibration is valid */
160 
163 
164  unsigned int _measure_interval;
165 
168 
169  float _range_ga;
171 
173  uint8_t _cntl_reg1;
174  uint8_t _cntl_reg2;
175  uint8_t _cntl_reg3;
176  uint8_t _cntl_reg4;
177  uint8_t _cntl_reg5;
178  uint8_t _range_bits;
181 
182 
183  /**
184  * @brief Performs the on-sensor scale calibration routine.
185  *
186  * @note The sensor will continue to provide measurements, these
187  * will however reflect the uncalibrated sensor state until
188  * the calibration routine has been completed.
189  *
190  * @param enable set to 1 to enable self-test strap, 0 to disable
191  */
192  int calibrate(struct file *file_pointer, unsigned enable);
193 
194  /**
195  * Collect the result of the most recent measurement.
196  */
197  int collect();
198 
199  /**
200  * Check the current scale calibration
201  *
202  * @return 0 if scale calibration is ok, 1 else
203  */
204  int check_scale();
205 
206  /**
207  * Check the current offset calibration
208  *
209  * @return 0 if offset calibration is ok, 1 else
210  */
211  int check_offset();
212 
213  /**
214  * @brief Performs a poll cycle; collect from the previous measurement
215  * and start a new one.
216  *
217  * This is the heart of the measurement state machine. This function
218  * alternately starts a measurement, or collects the data from the
219  * previous measurement.
220  *
221  * When the interval between measurements is greater than the minimum
222  * measurement interval, a gap is inserted between collection
223  * and measurement to provide the most recent measurement possible
224  * at the next interval.
225  */
226  void Run() override;
227 
228  /**
229  * Issue a measurement command.
230  *
231  * @return OK if the measurement command was successful.
232  */
233  int measure();
234 
235  /**
236  * @brief Resets the device
237  */
238  int reset();
239 
240  /**
241  * @brief Initialises the automatic measurement state machine and start it.
242  *
243  * @note This function is called at open and error time. It might make sense
244  * to make it more aggressive about resetting the bus in case of errors.
245  */
246  void start();
247 
248  /**
249  * @brief Performs the on-sensor scale calibration routine.
250  *
251  * @note The sensor will continue to provide measurements, these
252  * will however reflect the uncalibrated sensor state until
253  * the calibration routine has been completed.
254  *
255  * @param enable set to 1 to enable self-test positive strap, -1 to enable
256  * negative strap, 0 to set to normal mode
257  */
258  int set_excitement(unsigned enable);
259 
260  /**
261  * @brief Sets the sensor internal range to handle at least the argument in Gauss.
262  *
263  * @param range The sensor range value to be set.
264  */
265  int set_range(unsigned range);
266 
267  /**
268  * @brief Reads a register.
269  *
270  * @param reg The register to read.
271  * @param val The value read.
272  * @return OK on read success.
273  */
274  int read_reg(uint8_t reg, uint8_t &val);
275 
276  /**
277  * @brief Writes a register.
278  *
279  * @param reg The register to write.
280  * @param val The value to write.
281  * @return OK on write success.
282  */
283  int write_reg(uint8_t reg, uint8_t val);
284 
285  /* this class has pointer data members, do not allow copying it */
286  LIS3MDL(const LIS3MDL &);
287 
288  LIS3MDL operator=(const LIS3MDL &);
289 }; // class LIS3MDL
void print_info()
Diagnostics - print some basic information about the driver.
Definition: lis3mdl.cpp:602
uint8_t _cntl_reg5
Definition: lis3mdl.h:177
int reset()
Resets the device.
Definition: lis3mdl.cpp:612
virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len)
Definition: lis3mdl.cpp:632
int _class_instance
Definition: lis3mdl.h:166
int read_reg(uint8_t reg, uint8_t &val)
Reads a register.
Definition: lis3mdl.cpp:807
uint8_t _range_bits
Definition: lis3mdl.h:178
uint8_t _cntl_reg3
Definition: lis3mdl.h:175
int write_reg(uint8_t reg, uint8_t val)
Writes a register.
Definition: lis3mdl.cpp:816
enum OPERATING_MODE _mode
Definition: lis3mdl.h:161
used for info()
Definition: lis3mdl.h:148
mag scaling factors; Vout = (Vin * Vscale) + Voffset
Definition: drv_mag.h:56
Device * _interface
Definition: lis3mdl.h:140
Device(const Device &)=delete
perf_counter_t _sample_perf
Definition: lis3mdl.h:155
bool _continuous_mode_set
Definition: lis3mdl.h:159
Vector rotation library.
High-resolution timer with callouts and timekeeping.
perf_counter_t _comms_errors
Definition: lis3mdl.h:152
uint8_t _cntl_reg4
Definition: lis3mdl.h:176
float _range_scale
Definition: lis3mdl.h:170
Abstract class for any character device.
Definition: CDev.hpp:60
void stop()
Stop the automatic measurement state machine.
Definition: lis3mdl.cpp:797
virtual int ioctl(struct file *file_pointer, int cmd, unsigned long arg)
Definition: lis3mdl.cpp:495
int set_excitement(unsigned enable)
Performs the on-sensor scale calibration routine.
Definition: lis3mdl.cpp:702
int measure()
Issue a measurement command.
Definition: lis3mdl.cpp:579
void Run() override
Performs a poll cycle; collect from the previous measurement and start a new one. ...
Definition: lis3mdl.cpp:441
Header common to all counters.
LIS3MDL_BUS
Definition: lis3mdl.h:98
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
perf_counter_t _range_errors
Definition: lis3mdl.h:154
uint8_t _temperature_counter
Definition: lis3mdl.h:179
struct mag_calibration_s _scale
Definition: lis3mdl.h:146
LIS3MDL(device::Device *interface, const char *path, enum Rotation rotation)
Definition: lis3mdl.cpp:45
perf_counter_t _conf_errors
Definition: lis3mdl.h:153
int check_offset()
Check the current offset calibration.
Definition: lis3mdl.cpp:289
enum Rotation _rotation
Definition: lis3mdl.h:162
int set_range(unsigned range)
Sets the sensor internal range to handle at least the argument in Gauss.
Definition: lis3mdl.cpp:735
LIS3MDL operator=(const LIS3MDL &)
void start()
Initialises the automatic measurement state machine and start it.
Definition: lis3mdl.cpp:785
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
device::Device * LIS3MDL_SPI_interface(int bus)
orb_advert_t _mag_topic
Definition: lis3mdl.h:150
float _range_ga
Definition: lis3mdl.h:169
int _orb_class_instance
Definition: lis3mdl.h:167
int calibrate(struct file *file_pointer, unsigned enable)
Performs the on-sensor scale calibration routine.
Definition: lis3mdl.cpp:117
virtual ~LIS3MDL()
Definition: lis3mdl.cpp:92
uint8_t _temperature_error_count
Definition: lis3mdl.h:180
int set_default_register_values()
Configures the device with default register values.
Definition: lis3mdl.cpp:690
uint8_t _cntl_reg1
Definition: lis3mdl.h:173
struct @83::@85::@87 file
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
uint8_t _check_state_cnt
Definition: lis3mdl.h:172
OPERATING_MODE
Definition: lis3mdl.h:105
int collect()
Collect the result of the most recent measurement.
Definition: lis3mdl.cpp:327
bool _calibrated
the calibration is valid
Definition: lis3mdl.h:158
virtual int init()
Definition: lis3mdl.cpp:468
device::Device * LIS3MDL_I2C_interface(int bus)
unsigned int _measure_interval
Definition: lis3mdl.h:164
uint8_t _cntl_reg2
Definition: lis3mdl.h:174
int check_scale()
Check the current scale calibration.
Definition: lis3mdl.cpp:308
Performance measuring tools.
Base class for devices connected via I2C.
ringbuffer::RingBuffer * _reports
Definition: lis3mdl.h:144
#define mag_report
Definition: drv_mag.h:53