PX4 Firmware
PX4 Autopilot Software http://px4.io
ADIS16477.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2018-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  * ADIS16477.hpp
36  *
37  */
38 
39 #pragma once
40 
41 #include <drivers/device/spi.h>
42 #include <ecl/geo/geo.h>
46 #include <perf/perf_counter.h>
47 #include <px4_platform_common/getopt.h>
48 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
49 
50 class ADIS16477 : public device::SPI, public px4::ScheduledWorkItem
51 {
52 public:
53  ADIS16477(int bus, uint32_t device, enum Rotation rotation = ROTATION_NONE);
54  virtual ~ADIS16477();
55 
56  virtual int init();
57 
58  void print_info();
59 
60 protected:
61  virtual int probe();
62 
63 private:
64 
67 
70 
71 #pragma pack(push, 1)
72  // Report conversation with in the ADIS16477, including command byte and interrupt status.
73  struct ADISReport {
74  uint16_t cmd;
75  uint16_t diag_stat;
76  int16_t gyro_x;
77  int16_t gyro_y;
78  int16_t gyro_z;
79  int16_t accel_x;
80  int16_t accel_y;
81  int16_t accel_z;
82  uint16_t temp;
83  uint16_t DATA_CNTR;
84  uint8_t checksum;
85  uint8_t _padding; // 16 bit SPI mode
86  };
87 #pragma pack(pop)
88 
89  /**
90  * Start automatic measurement.
91  */
92  void start();
93 
94  /**
95  * Stop automatic measurement.
96  */
97  void stop();
98 
99  /**
100  * Reset chip.
101  *
102  * Resets the chip and measurements ranges, but not scale and offset.
103  */
104  int reset();
105 
106  void Run() override;
107 
108  static int data_ready_interrupt(int irq, void *context, void *arg);
109 
110  /**
111  * Fetch measurements from the sensor and update the report buffers.
112  */
113  int measure();
114 
115  uint16_t read_reg16(uint8_t reg);
116 
117  void write_reg(uint8_t reg, uint8_t value);
118  void write_reg16(uint8_t reg, uint16_t value);
119 
120  // ADIS16477 onboard self test
121  bool self_test_memory();
122  bool self_test_sensor();
123 
124 };
Definition of geo / math functions to perform geodesic calculations.
int reset()
Reset chip.
Definition: ADIS16477.cpp:103
perf_counter_t _sample_perf
Definition: ADIS16477.hpp:68
void print_info()
Definition: ADIS16477.cpp:389
void write_reg16(uint8_t reg, uint16_t value)
Definition: ADIS16477.cpp:262
bool self_test_sensor()
Definition: ADIS16477.cpp:217
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
Vector rotation library.
ADIS16477(int bus, uint32_t device, enum Rotation rotation=ROTATION_NONE)
Definition: ADIS16477.cpp:56
void write_reg(uint8_t reg, uint8_t value)
Definition: ADIS16477.cpp:253
Header common to all counters.
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
uint16_t read_reg16(uint8_t reg)
Definition: ADIS16477.cpp:239
static int data_ready_interrupt(int irq, void *context, void *arg)
Definition: ADIS16477.cpp:302
PX4Accelerometer _px4_accel
Definition: ADIS16477.hpp:65
void start()
Start automatic measurement.
Definition: ADIS16477.cpp:276
int measure()
Fetch measurements from the sensor and update the report buffers.
Definition: ADIS16477.cpp:320
void Run() override
Definition: ADIS16477.cpp:313
void stop()
Stop automatic measurement.
Definition: ADIS16477.cpp:291
perf_counter_t _bad_transfers
Definition: ADIS16477.hpp:69
PX4Gyroscope _px4_gyro
Definition: ADIS16477.hpp:66
virtual ~ADIS16477()
Definition: ADIS16477.cpp:78
bool self_test_memory()
Definition: ADIS16477.cpp:195
virtual int probe()
Definition: ADIS16477.cpp:166
virtual int init()
Definition: ADIS16477.cpp:89
Performance measuring tools.