PX4 Firmware
PX4 Autopilot Software http://px4.io
FXAS21002C.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 FXAS21002C.hpp
36  * Driver for the NXP FXAS21002C 3-Axis Digital Angular Rate Gyroscope
37  * connected via SPI
38  */
39 
40 #pragma once
41 
42 #include <drivers/device/spi.h>
44 #include <perf/perf_counter.h>
45 #include <px4_platform_common/getopt.h>
46 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
47 
48 
49 class FXAS21002C : public device::SPI, public px4::ScheduledWorkItem
50 {
51 public:
52  FXAS21002C(int bus, uint32_t device, enum Rotation rotation);
53  virtual ~FXAS21002C();
54 
55  virtual int init();
56 
57  /**
58  * Diagnostics - print some basic information about the driver.
59  */
60  void print_info();
61 
62  /**
63  * dump register values
64  */
65  void print_registers();
66 
67  /**
68  * deliberately trigger an error
69  */
70  void test_error();
71 
72 protected:
73  virtual int probe();
74 
75 private:
76 
78 
79  unsigned _current_rate{800};
80 
81  unsigned _read{0};
82 
87 
88  uint8_t _register_wait{0};
89 
90  /* this is used to support runtime checking of key
91  *configuration registers to detect SPI bus errors and sensor
92  * reset
93  */
94  static constexpr int FXAS21002C_NUM_CHECKED_REGISTERS{6};
95 
97  uint8_t _checked_next{0};
98 
99  /**
100  * Start automatic measurement.
101  */
102  void start();
103 
104  /**
105  * Stop automatic measurement.
106  */
107  void stop();
108 
109  /**
110  * Reset chip.
111  *
112  * Resets the chip and measurements ranges, but not scale and offset.
113  */
114  void reset();
115 
116  /**
117  * Put the chip In stand by
118  */
119  void set_standby(int rate, bool standby_true);
120 
121  void Run() override;
122 
123  /**
124  * check key registers for correct values
125  */
126  void check_registers(void);
127 
128  /**
129  * Fetch accel measurements from the sensor and update the report ring.
130  */
131  void measure();
132 
133  /**
134  * Read a register from the FXAS21002C
135  *
136  * @param The register to read.
137  * @return The value that was read.
138  */
139  uint8_t read_reg(unsigned reg);
140 
141  /**
142  * Write a register in the FXAS21002C
143  *
144  * @param reg The register to write.
145  * @param value The new value to write.
146  */
147  void write_reg(unsigned reg, uint8_t value);
148 
149  /**
150  * Modify a register in the FXAS21002C
151  *
152  * Bits are cleared before bits are set.
153  *
154  * @param reg The register to modify.
155  * @param clearbits Bits in the register to clear.
156  * @param setbits Bits in the register to set.
157  */
158  void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits);
159 
160  /**
161  * Write a register in the FXAS21002C, updating _checked_values
162  *
163  * @param reg The register to write.
164  * @param value The new value to write.
165  */
166  void write_checked_reg(unsigned reg, uint8_t value);
167 
168  /**
169  * Set the FXAS21002C measurement range.
170  *
171  * @param max_dps The measurement range is set to permit reading at least
172  * this rate in degrees per second.
173  * Zero selects the maximum supported range.
174  * @return OK if the value can be supported, -ERANGE otherwise.
175  */
176  int set_range(unsigned max_dps);
177 
178  /**
179  * Set the FXAS21002C internal sampling frequency.
180  *
181  * @param frequency The internal sampling frequency is set to not less than
182  * this value.
183  * Zero selects the maximum rate supported.
184  * @return OK if the value can be supported.
185  */
186  int set_samplerate(unsigned frequency);
187 
188  /*
189  set onchip low pass filter frequency
190  */
191  void set_onchip_lowpass_filter(int frequency_hz);
192 };
perf_counter_t _errors
Definition: FXAS21002C.hpp:84
FXAS21002C(int bus, uint32_t device, enum Rotation rotation)
Definition: FXAS21002C.cpp:189
void test_error()
deliberately trigger an error
Definition: FXAS21002C.cpp:654
virtual int probe()
Definition: FXAS21002C.cpp:261
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
Modify a register in the FXAS21002C.
Definition: FXAS21002C.cpp:311
void start()
Start automatic measurement.
Definition: FXAS21002C.cpp:474
void set_standby(int rate, bool standby_true)
Put the chip In stand by.
Definition: FXAS21002C.cpp:364
void print_registers()
dump register values
Definition: FXAS21002C.cpp:618
uint8_t _checked_next
Definition: FXAS21002C.hpp:97
void check_registers(void)
check key registers for correct values
Definition: FXAS21002C.cpp:497
void reset()
Reset chip.
Definition: FXAS21002C.cpp:230
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
void write_reg(unsigned reg, uint8_t value)
Write a register in the FXAS21002C.
Definition: FXAS21002C.cpp:288
perf_counter_t _sample_perf
Definition: FXAS21002C.hpp:83
uint8_t read_reg(unsigned reg)
Read a register from the FXAS21002C.
Definition: FXAS21002C.cpp:275
void stop()
Stop automatic measurement.
Definition: FXAS21002C.cpp:484
PX4Gyroscope _px4_gyro
Definition: FXAS21002C.hpp:77
Header common to all counters.
virtual ~FXAS21002C()
Definition: FXAS21002C.cpp:201
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
perf_counter_t _bad_registers
Definition: FXAS21002C.hpp:85
void set_onchip_lowpass_filter(int frequency_hz)
Definition: FXAS21002C.cpp:438
int set_range(unsigned max_dps)
Set the FXAS21002C measurement range.
Definition: FXAS21002C.cpp:320
virtual int init()
Definition: FXAS21002C.cpp:214
void measure()
Fetch accel measurements from the sensor and update the report ring.
Definition: FXAS21002C.cpp:527
void Run() override
Definition: FXAS21002C.cpp:490
uint8_t _checked_values[FXAS21002C_NUM_CHECKED_REGISTERS]
Definition: FXAS21002C.hpp:96
int set_samplerate(unsigned frequency)
Set the FXAS21002C internal sampling frequency.
Definition: FXAS21002C.cpp:386
unsigned _current_rate
Definition: FXAS21002C.hpp:79
void print_info()
Diagnostics - print some basic information about the driver.
Definition: FXAS21002C.cpp:594
perf_counter_t _duplicates
Definition: FXAS21002C.hpp:86
uint8_t _register_wait
Definition: FXAS21002C.hpp:88
void write_checked_reg(unsigned reg, uint8_t value)
Write a register in the FXAS21002C, updating _checked_values.
Definition: FXAS21002C.cpp:299
static constexpr int FXAS21002C_NUM_CHECKED_REGISTERS
Definition: FXAS21002C.hpp:94
unsigned _read
Definition: FXAS21002C.hpp:81
Performance measuring tools.