PX4 Firmware
PX4 Autopilot Software http://px4.io
LSM303AGR.hpp
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 #ifndef DRIVERS_IMU_LSM303AGR_LSM303AGR_HPP_
35 #define DRIVERS_IMU_LSM303AGR_LSM303AGR_HPP_
36 
37 #include <drivers/drv_hrt.h>
38 #include <drivers/device/spi.h>
39 #include <drivers/drv_mag.h>
44 #include <perf/perf_counter.h>
45 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
46 #include <systemlib/err.h>
47 
48 // Register mapping
49 static constexpr uint8_t WHO_AM_I_M = 0x4F;
50 
51 static constexpr uint8_t CFG_REG_A_M = 0x60;
52 
54  uint8_t
55  : 1, // unused
56  : 1, // unused
57  SOFT_RST : 1,
58  LP : 1,
59  ODR1 : 1,
60  ODR0 : 1,
61  MD1 : 1,
62  MD0 : 1;
63 };
64 
65 static constexpr uint8_t CFG_REG_A_M_SOFT_RST = (1 << 5);
66 static constexpr uint8_t CFG_REG_A_M_ODR1 = (1 << 3);
67 static constexpr uint8_t CFG_REG_A_M_ODR0 = (1 << 2);
68 static constexpr uint8_t CFG_REG_A_M_MD1 = (1 << 1);
69 static constexpr uint8_t CFG_REG_A_M_MD0 = (1 << 0);
70 
71 static constexpr uint8_t CFG_REG_B_M = 0x61;
72 static constexpr uint8_t CFG_REG_B_M_OFF_CANC = (1 << 1);
73 static constexpr uint8_t CFG_REG_B_M_OFF_LPF = (1 << 0);
74 
75 static constexpr uint8_t CFG_REG_C_M = 0x62;
76 static constexpr uint8_t CFG_REG_C_M_I2C_DIS = (1 << 5);
77 static constexpr uint8_t CFG_REG_C_M_BDU = (1 << 4);
78 static constexpr uint8_t CFG_REG_C_M_Self_test = (1 << 1);
79 
80 static constexpr uint8_t STATUS_REG_M = 0x67;
81 static constexpr uint8_t STATUS_REG_M_Zyxda = (1 << 3);
82 
83 // Magnetometer output registers
84 static constexpr uint8_t OUTX_L_REG_M = 0x68;
85 static constexpr uint8_t OUTX_H_REG_M = 0x69;
86 static constexpr uint8_t OUTY_L_REG_M = 0x6A;
87 static constexpr uint8_t OUTY_H_REG_M = 0x6B;
88 static constexpr uint8_t OUTZ_L_REG_M = 0x6C;
89 static constexpr uint8_t OUTZ_H_REG_M = 0x6D;
90 
91 class LSM303AGR : public device::SPI, public px4::ScheduledWorkItem
92 {
93 public:
94  LSM303AGR(int bus, const char *path, uint32_t device, enum Rotation rotation);
95  virtual ~LSM303AGR();
96 
97  virtual int init();
98 
99  virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
100 
101  /**
102  * Diagnostics - print some basic information about the driver.
103  */
104  void print_info();
105 
106 protected:
107  virtual int probe();
108 
109 private:
110 
111  bool _collect_phase{false};
112 
113  unsigned _measure_interval{0};
114 
115  unsigned _call_mag_interval{0};
116 
117  mag_calibration_s _mag_scale{};
118 
119  static constexpr float _mag_range_scale{1.5f / 1000.0f}; // 1.5 milligauss/LSB
120  static constexpr float _mag_range_ga{49.152f};
121 
122  int _class_instance{-1};
123 
124  unsigned _mag_samplerate{100};
125 
129 
130  enum Rotation _rotation;
131 
132  orb_advert_t _mag_topic{nullptr};
134 
135  /**
136  * Start automatic measurement.
137  */
138  void start();
139 
140  /**
141  * Stop automatic measurement.
142  */
143  void stop();
144 
145  /**
146  * Reset chip.
147  *
148  * Resets the chip and measurements ranges, but not scale and offset.
149  */
150  int reset();
151 
152 
153  bool self_test();
154 
155  /**
156  * Issue a measurement command.
157  *
158  * @return OK if the measurement command was successful.
159  */
160  void measure();
161 
162  /**
163  * Collect the result of the most recent measurement.
164  */
165  int collect();
166 
167  /**
168  * Perform a poll cycle; collect from the previous measurement
169  * and start a new one.
170  *
171  * This is the heart of the measurement state machine. This function
172  * alternately starts a measurement, or collects the data from the
173  * previous measurement.
174  *
175  * When the interval between measurements is greater than the minimum
176  * measurement interval, a gap is inserted between collection
177  * and measurement to provide the most recent measurement possible
178  * at the next interval.
179  */
180  void Run() override;
181 
182  /**
183  * Read a register from the LSM303AGR
184  *
185  * @param The register to read.
186  * @return The value that was read.
187  */
188  uint8_t read_reg(unsigned reg);
189 
190  /**
191  * Write a register in the LSM303AGR
192  *
193  * @param reg The register to write.
194  * @param value The new value to write.
195  */
196  void write_reg(unsigned reg, uint8_t value);
197 
198  /* this class cannot be copied */
199  LSM303AGR(const LSM303AGR &);
200  LSM303AGR operator=(const LSM303AGR &);
201 };
202 
203 #endif /* DRIVERS_IMU_LSM303AGR_LSM303AGR_HPP_ */
static constexpr uint8_t CFG_REG_C_M_I2C_DIS
Definition: LSM303AGR.hpp:76
static constexpr uint8_t CFG_REG_A_M_SOFT_RST
Definition: LSM303AGR.hpp:65
static constexpr uint8_t CFG_REG_C_M_BDU
Definition: LSM303AGR.hpp:77
static constexpr uint8_t CFG_REG_A_M_ODR0
Definition: LSM303AGR.hpp:67
static int _mag_orb_class_instance
instance handle for mag devices
mag scaling factors; Vout = (Vin * Vscale) + Voffset
Definition: drv_mag.h:56
static constexpr uint8_t OUTY_H_REG_M
Definition: LSM303AGR.hpp:87
int reset(enum LPS22HB_BUS busid)
Reset the driver.
static void stop()
Definition: dataman.cpp:1491
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
Vector rotation library.
High-resolution timer with callouts and timekeeping.
static constexpr uint8_t CFG_REG_A_M_MD1
Definition: LSM303AGR.hpp:68
static constexpr uint8_t CFG_REG_A_M
Definition: LSM303AGR.hpp:51
uint8_t SOFT_RST
Definition: LSM303AGR.hpp:55
static constexpr uint8_t WHO_AM_I_M
Definition: LSM303AGR.hpp:49
perf_counter_t _bad_values
Definition: LSM303AGR.hpp:128
static constexpr uint8_t CFG_REG_B_M_OFF_CANC
Definition: LSM303AGR.hpp:72
static constexpr uint8_t CFG_REG_C_M_Self_test
Definition: LSM303AGR.hpp:78
Header common to all counters.
void init()
Activates/configures the hardware registers.
static constexpr uint8_t CFG_REG_A_M_ODR1
Definition: LSM303AGR.hpp:66
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
static constexpr uint8_t CFG_REG_C_M
Definition: LSM303AGR.hpp:75
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
static constexpr uint8_t OUTY_L_REG_M
Definition: LSM303AGR.hpp:86
static constexpr uint8_t OUTX_L_REG_M
Definition: LSM303AGR.hpp:84
static int start()
Definition: dataman.cpp:1452
A resettable integrator.
static constexpr uint8_t OUTZ_L_REG_M
Definition: LSM303AGR.hpp:88
static constexpr uint8_t OUTZ_H_REG_M
Definition: LSM303AGR.hpp:89
struct @83::@85::@87 file
perf_counter_t _mag_sample_perf
Definition: LSM303AGR.hpp:126
static constexpr uint8_t STATUS_REG_M_Zyxda
Definition: LSM303AGR.hpp:81
static constexpr uint8_t STATUS_REG_M
Definition: LSM303AGR.hpp:80
static constexpr uint8_t CFG_REG_B_M
Definition: LSM303AGR.hpp:71
static constexpr uint8_t CFG_REG_B_M_OFF_LPF
Definition: LSM303AGR.hpp:73
perf_counter_t _bad_registers
Definition: LSM303AGR.hpp:127
static constexpr uint8_t OUTX_H_REG_M
Definition: LSM303AGR.hpp:85
static constexpr uint8_t CFG_REG_A_M_MD0
Definition: LSM303AGR.hpp:69
Performance measuring tools.