PX4 Firmware
PX4 Autopilot Software http://px4.io
rm3100.h
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  * @file rm3100.h
36  *
37  * Shared defines for the RM3100 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 
51 #include <perf/perf_counter.h>
52 #include <px4_platform_common/defines.h>
53 #include <systemlib/err.h>
54 
55 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
56 
57 /**
58  * RM3100 internal constants and data structures.
59  */
60 
61 /* At 146 Hz we encounter errors, 100 Hz is safer */
62 #define RM3100_CONVERSION_INTERVAL 10000 // Microseconds, corresponds to 100 Hz (cycle count 200 on 3 axis)
63 #define UTESLA_TO_GAUSS 100.0f
64 #define RM3100_SENSITIVITY 75.0f
65 
66 #define ADDR_POLL 0x00
67 #define ADDR_CMM 0x01
68 #define ADDR_CCX 0x04
69 #define ADDR_CCY 0x06
70 #define ADDR_CCZ 0x08
71 #define ADDR_TMRC 0x0B
72 #define ADDR_MX 0x24
73 #define ADDR_MY 0x27
74 #define ADDR_MZ 0x2A
75 #define ADDR_BIST 0x33
76 #define ADDR_STATUS 0x34
77 #define ADDR_HSHAKE 0x35
78 #define ADDR_REVID 0x36
79 
80 #define CCX_DEFAULT_MSB 0x00
81 #define CCX_DEFAULT_LSB 0xC8
82 #define CCY_DEFAULT_MSB CCX_DEFAULT_MSB
83 #define CCY_DEFAULT_LSB CCX_DEFAULT_LSB
84 #define CCZ_DEFAULT_MSB CCX_DEFAULT_MSB
85 #define CCZ_DEFAULT_LSB CCX_DEFAULT_LSB
86 #define CMM_DEFAULT 0x70 // No continuous mode
87 #define CONTINUOUS_MODE (1 << 0)
88 #define POLLING_MODE (0 << 0)
89 #define TMRC_DEFAULT 0x94
90 #define BIST_SELFTEST 0x8F
91 #define BIST_DEFAULT 0x00
92 #define BIST_XYZ_OK ((1 << 4) | (1 << 5) | (1 << 6))
93 #define STATUS_DRDY (1 << 7)
94 #define POLL_XYZ 0x70
95 #define RM3100_REVID 0x22
96 
97 #define NUM_BUS_OPTIONS (sizeof(bus_options)/sizeof(bus_options[0]))
98 
99 /* interface factories */
100 extern device::Device *RM3100_SPI_interface(int bus);
101 extern device::Device *RM3100_I2C_interface(int bus);
102 typedef device::Device *(*RM3100_constructor)(int);
103 
110 };
111 
115 };
116 
117 
118 class RM3100 : public device::CDev, public px4::ScheduledWorkItem
119 {
120 public:
121  RM3100(device::Device *interface, const char *path, enum Rotation rotation);
122 
123  virtual ~RM3100();
124 
125  virtual int init();
126 
127  virtual int ioctl(struct file *file_pointer, int cmd, unsigned long arg);
128 
129  virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len);
130 
131  /**
132  * Diagnostics - print some basic information about the driver.
133  */
134  void print_info();
135 
136  /**
137  * Configures the device with default register values.
138  */
140 
141  /**
142  * Stop the automatic measurement state machine.
143  */
144  void stop();
145 
146 protected:
148 
149 private:
150 
151  ringbuffer::RingBuffer *_reports;
152 
154 
155  struct mag_report _last_report {}; /**< used for info() */
156 
158 
163 
164  /* status reporting */
165  bool _calibrated; /**< the calibration is valid */
167 
170 
171  unsigned int _measure_interval;
172 
175 
177 
179 
180  /**
181  * Collect the result of the most recent measurement.
182  */
183  int collect();
184 
185  /**
186  * Run sensor self-test
187  *
188  * @return 0 if self-test is ok, 1 else
189  */
190  int self_test();
191 
192  /**
193  * Check whether new data is available or not
194  *
195  * @return 0 if new data is available, 1 else
196  */
197  int check_measurement();
198 
199  /**
200  * Converts int24_t stored in 32-bit container to int32_t
201  */
202  void convert_signed(int32_t *n);
203 
204  /**
205  * @brief Performs a poll cycle; collect from the previous measurement
206  * and start a new one.
207  *
208  * This is the heart of the measurement state machine. This function
209  * alternately starts a measurement, or collects the data from the
210  * previous measurement.
211  *
212  * When the interval between measurements is greater than the minimum
213  * measurement interval, a gap is inserted between collection
214  * and measurement to provide the most recent measurement possible
215  * at the next interval.
216  */
217  void Run() override;
218 
219  /**
220  * Issue a measurement command.
221  *
222  * @return OK if the measurement command was successful.
223  */
224  int measure();
225 
226  /**
227  * @brief Resets the device
228  */
229  int reset();
230 
231  /**
232  * @brief Initialises the automatic measurement state machine and start it.
233  *
234  * @note This function is called at open and error time. It might make sense
235  * to make it more aggressive about resetting the bus in case of errors.
236  */
237  void start();
238 
239  /* this class has pointer data members, do not allow copying it */
240  RM3100(const RM3100 &);
241 
242  RM3100 operator=(const RM3100 &);
243 }; // class RM3100
perf_counter_t _conf_errors
Definition: rm3100.h:160
int collect()
Collect the result of the most recent measurement.
Definition: rm3100.cpp:169
virtual int read(struct file *file_pointer, char *buffer, size_t buffer_len)
Definition: rm3100.cpp:501
enum Rotation _rotation
Definition: rm3100.h:169
int self_test()
Run sensor self-test.
Definition: rm3100.cpp:102
perf_counter_t _sample_perf
Definition: rm3100.h:162
bool _calibrated
the calibration is valid
Definition: rm3100.h:165
void stop()
Stop the automatic measurement state machine.
Definition: rm3100.cpp:601
device::Device * RM3100_I2C_interface(int bus)
enum OPERATING_MODE _mode
Definition: rm3100.h:168
RM3100_BUS
Definition: rm3100.h:104
perf_counter_t _comms_errors
Definition: rm3100.h:159
mag scaling factors; Vout = (Vin * Vscale) + Voffset
Definition: drv_mag.h:56
bool _continuous_mode_set
Definition: rm3100.h:166
virtual int ioctl(struct file *file_pointer, int cmd, unsigned long arg)
Definition: rm3100.cpp:350
Device(const Device &)=delete
struct mag_calibration_s _scale
Definition: rm3100.h:153
Definition: rm3100.h:118
Vector rotation library.
High-resolution timer with callouts and timekeeping.
int reset()
Resets the device.
Definition: rm3100.cpp:487
Abstract class for any character device.
Definition: CDev.hpp:60
virtual ~RM3100()
Definition: rm3100.cpp:81
int set_default_register_values()
Configures the device with default register values.
Definition: rm3100.cpp:559
Definition: rm3100.h:114
RM3100 operator=(const RM3100 &)
Header common to all counters.
virtual int init()
Definition: rm3100.cpp:317
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
orb_advert_t _mag_topic
Definition: rm3100.h:157
void convert_signed(int32_t *n)
Converts int24_t stored in 32-bit container to int32_t.
Definition: rm3100.cpp:281
RM3100(device::Device *interface, const char *path, enum Rotation rotation)
Definition: rm3100.cpp:44
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
void print_info()
Diagnostics - print some basic information about the driver.
Definition: rm3100.cpp:477
unsigned int _measure_interval
Definition: rm3100.h:171
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
int check_measurement()
Check whether new data is available or not.
Definition: rm3100.cpp:154
used for info()
Definition: rm3100.h:155
perf_counter_t _range_errors
Definition: rm3100.h:161
ringbuffer::RingBuffer * _reports
Definition: rm3100.h:151
int _orb_class_instance
Definition: rm3100.h:174
Device * _interface
Definition: rm3100.h:147
void Run() override
Performs a poll cycle; collect from the previous measurement and start a new one. ...
Definition: rm3100.cpp:290
int measure()
Issue a measurement command.
Definition: rm3100.cpp:439
uint8_t _check_state_cnt
Definition: rm3100.h:178
struct @83::@85::@87 file
int _class_instance
Definition: rm3100.h:173
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
OPERATING_MODE
Definition: lis3mdl.h:105
void start()
Initialises the automatic measurement state machine and start it.
Definition: rm3100.cpp:588
float _range_scale
Definition: rm3100.h:176
Performance measuring tools.
device::Device * RM3100_SPI_interface(int bus)
Base class for devices connected via I2C.
#define mag_report
Definition: drv_mag.h:53