PX4 Firmware
PX4 Autopilot Software http://px4.io
FXOS8701CQ.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2017-2019 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 FXOS8701CQ.hpp
36  * Driver for the NXP FXOS8701CQ 6-axis sensor with integrated linear accelerometer and
37  * magnetometer connected via SPI.
38  */
39 
40 #pragma once
41 
42 #include <drivers/device/spi.h>
44 #include <lib/ecl/geo/geo.h>
45 #include <lib/perf/perf_counter.h>
46 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
47 
48 #if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
50 #endif
51 
52 /* SPI protocol address bits */
53 #define DIR_READ(a) ((a) & 0x7f)
54 #define DIR_WRITE(a) ((a) | (1 << 7))
55 #define ADDR_7(a) ((a) & (1 << 7))
56 #define swap16(w) __builtin_bswap16((w))
57 #define swap16RightJustify14(w) (((int16_t)swap16(w)) >> 2)
58 
59 #define FXOS8701CQ_DR_STATUS 0x00
60 # define DR_STATUS_ZYXDR (1 << 3)
61 
62 #define FXOS8701CQ_OUT_X_MSB 0x01
63 
64 #define FXOS8701CQ_XYZ_DATA_CFG 0x0e
65 # define XYZ_DATA_CFG_FS_SHIFTS 0
66 # define XYZ_DATA_CFG_FS_MASK (3 << XYZ_DATA_CFG_FS_SHIFTS)
67 # define XYZ_DATA_CFG_FS_2G (0 << XYZ_DATA_CFG_FS_SHIFTS)
68 # define XYZ_DATA_CFG_FS_4G (1 << XYZ_DATA_CFG_FS_SHIFTS)
69 # define XYZ_DATA_CFG_FS_8G (2 << XYZ_DATA_CFG_FS_SHIFTS)
70 
71 #define FXOS8701CQ_WHOAMI 0x0d
72 # define FXOS8700CQ_WHOAMI_VAL 0xC7
73 # define FXOS8701CQ_WHOAMI_VAL 0xCA
74 
75 #define FXOS8701CQ_CTRL_REG1 0x2a
76 # define CTRL_REG1_ACTIVE (1 << 0)
77 # define CTRL_REG1_DR_SHIFTS 3
78 # define CTRL_REG1_DR_MASK (7 << CTRL_REG1_DR_SHIFTS)
79 # define CTRL_REG1_DR(n) (((n) & 7) << CTRL_REG1_DR_SHIFTS)
80 #define FXOS8701CQ_CTRL_REG2 0x2b
81 # define CTRL_REG2_AUTO_INC (1 << 5)
82 
83 #define FXOS8701CQ_M_DR_STATUS 0x32
84 # define M_DR_STATUS_ZYXDR (1 << 3)
85 #define FXOS8701CQ_M_OUT_X_MSB 0x33
86 #define FXOS8701CQ_TEMP 0x51
87 #define FXOS8701CQ_M_CTRL_REG1 0x5b
88 # define M_CTRL_REG1_HMS_SHIFTS 0
89 # define M_CTRL_REG1_HMS_MASK (3 << M_CTRL_REG1_HMS_SHIFTS)
90 # define M_CTRL_REG1_HMS_A (0 << M_CTRL_REG1_HMS_SHIFTS)
91 # define M_CTRL_REG1_HMS_M (1 << M_CTRL_REG1_HMS_SHIFTS)
92 # define M_CTRL_REG1_HMS_AM (3 << M_CTRL_REG1_HMS_SHIFTS)
93 # define M_CTRL_REG1_OS_SHIFTS 2
94 # define M_CTRL_REG1_OS_MASK (7 << M_CTRL_REG1_HMS_SHIFTS)
95 # define M_CTRL_REG1_OS(n) (((n) & 7) << M_CTRL_REG1_OS_SHIFTS)
96 
97 #define FXOS8701CQ_M_CTRL_REG2 0x5c
98 #define FXOS8701CQ_M_CTRL_REG3 0x5d
99 
100 #define DEF_REG(r) {r, #r}
101 
102 /* default values for this device */
103 #define FXOS8701C_ACCEL_DEFAULT_RANGE_G 8
104 #define FXOS8701C_ACCEL_DEFAULT_RATE 400 /* ODR is 400 in Hybird mode (accel + mag) */
105 
106 /*
107  we set the timer interrupt to run a bit faster than the desired
108  sample rate and then throw away duplicates using the data ready bit.
109  This time reduction is enough to cope with worst case timing jitter
110  due to other timers
111  */
112 #define FXOS8701C_TIMER_REDUCTION 240
113 
114 class FXOS8701CQ : public device::SPI, public px4::ScheduledWorkItem
115 {
116 public:
117  FXOS8701CQ(int bus, uint32_t device, enum Rotation rotation);
118  virtual ~FXOS8701CQ();
119 
120  virtual int init();
121 
122  void print_info();
123  void print_registers();
124  void test_error();
125 
126 protected:
127  virtual int probe();
128 
129 private:
130 
131  void Run() override;
132 
133  void start();
134  void stop();
135  void reset();
136 
137  /**
138  * check key registers for correct values
139  */
140  void check_registers();
141 
142  /**
143  * Read a register from the FXOS8701C
144  *
145  * @param The register to read.
146  * @return The value that was read.
147  */
148  uint8_t read_reg(unsigned reg);
149 
150  /**
151  * Write a register in the FXOS8701C
152  *
153  * @param reg The register to write.
154  * @param value The new value to write.
155  */
156  void write_reg(unsigned reg, uint8_t value);
157 
158  /**
159  * Modify a register in the FXOS8701C
160  *
161  * Bits are cleared before bits are set.
162  *
163  * @param reg The register to modify.
164  * @param clearbits Bits in the register to clear.
165  * @param setbits Bits in the register to set.
166  */
167  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
168 
169  /**
170  * Write a register in the FXOS8701C, updating _checked_values
171  *
172  * @param reg The register to write.
173  * @param value The new value to write.
174  */
175  void write_checked_reg(unsigned reg, uint8_t value);
176 
177  /**
178  * Set the FXOS8701C accel measurement range.
179  *
180  * @param max_g The measurement range of the accel is in g (9.81m/s^2)
181  * Zero selects the maximum supported range.
182  * @return OK if the value can be supported, -ERANGE otherwise.
183  */
184  int accel_set_range(unsigned max_g);
185 
186  /**
187  * Set the FXOS8701C mag measurement range.
188  *
189  * @param max_ga The measurement range of the mag is in Ga
190  * Zero selects the maximum supported range.
191  * @return OK if the value can be supported, -ERANGE otherwise.
192  */
193  int mag_set_range(unsigned max_g);
194 
195  /**
196  * Set the FXOS8701C internal accel and mag sampling frequency.
197  *
198  * @param frequency The internal accel and mag sampling frequency is set to not less than
199  * this value.
200  * Zero selects the maximum rate supported.
201  * @return OK if the value can be supported.
202  */
203  int accel_set_samplerate(unsigned frequency);
204 
205 
207 
208 #if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
212 #endif
213 
215 
219 
220  uint8_t _register_wait{0};
221 
222  // this is used to support runtime checking of key
223  // configuration registers to detect SPI bus errors and sensor
224  // reset
225  static constexpr int FXOS8701C_NUM_CHECKED_REGISTERS{5};
228  uint8_t _checked_next{0};
229 
230 };
uint8_t read_reg(unsigned reg)
Read a register from the FXOS8701C.
Definition: FXOS8701CQ.cpp:147
void write_reg(unsigned reg, uint8_t value)
Write a register in the FXOS8701C.
Definition: FXOS8701CQ.cpp:161
virtual int init()
Definition: FXOS8701CQ.cpp:94
perf_counter_t _accel_duplicates
Definition: FXOS8701CQ.hpp:218
void Run() override
Definition: FXOS8701CQ.cpp:331
Definition of geo / math functions to perform geodesic calculations.
void stop()
Definition: FXOS8701CQ.cpp:295
PX4Magnetometer _px4_mag
Definition: FXOS8701CQ.hpp:209
void print_registers()
Definition: FXOS8701CQ.cpp:435
void start()
Definition: FXOS8701CQ.cpp:285
static constexpr int FXOS8701C_NUM_CHECKED_REGISTERS
Definition: FXOS8701CQ.hpp:225
uint8_t _checked_next
Definition: FXOS8701CQ.hpp:228
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
virtual int probe()
Definition: FXOS8701CQ.cpp:132
perf_counter_t _mag_sample_perf
Definition: FXOS8701CQ.hpp:211
FXOS8701CQ(int bus, uint32_t device, enum Rotation rotation)
Definition: FXOS8701CQ.cpp:56
void write_checked_reg(unsigned reg, uint8_t value)
Write a register in the FXOS8701C, updating _checked_values.
Definition: FXOS8701CQ.cpp:173
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
Modify a register in the FXOS8701C.
Definition: FXOS8701CQ.cpp:185
perf_counter_t _accel_sample_perf
Definition: FXOS8701CQ.hpp:216
Header common to all counters.
perf_counter_t _bad_registers
Definition: FXOS8701CQ.hpp:217
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
hrt_abstime _mag_last_measure
Definition: FXOS8701CQ.hpp:210
#define FXOS8701C_ACCEL_DEFAULT_RATE
Definition: FXOS8701CQ.hpp:104
void reset()
Definition: FXOS8701CQ.cpp:112
void check_registers()
check key registers for correct values
Definition: FXOS8701CQ.cpp:301
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
unsigned _accel_samplerate
Definition: FXOS8701CQ.hpp:214
uint8_t _checked_values[FXOS8701C_NUM_CHECKED_REGISTERS]
Definition: FXOS8701CQ.hpp:227
int accel_set_samplerate(unsigned frequency)
Set the FXOS8701C internal accel and mag sampling frequency.
Definition: FXOS8701CQ.cpp:242
uint8_t _register_wait
Definition: FXOS8701CQ.hpp:220
virtual ~FXOS8701CQ()
Definition: FXOS8701CQ.cpp:78
static const uint8_t _checked_registers[FXOS8701C_NUM_CHECKED_REGISTERS]
Definition: FXOS8701CQ.hpp:226
int accel_set_range(unsigned max_g)
Set the FXOS8701C accel measurement range.
Definition: FXOS8701CQ.cpp:194
PX4Accelerometer _px4_accel
Definition: FXOS8701CQ.hpp:206
void test_error()
Definition: FXOS8701CQ.cpp:460
Performance measuring tools.
int mag_set_range(unsigned max_g)
Set the FXOS8701C mag measurement range.
Definition: FXOS8701CQ.cpp:230
void print_info()
Definition: FXOS8701CQ.cpp:410