PX4 Firmware
PX4 Autopilot Software http://px4.io
LPS22HB.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 #pragma once
35 
36 #include <cstring>
37 
39 #include <drivers/device/i2c.h>
40 #include <drivers/device/spi.h>
41 #include <drivers/drv_baro.h>
42 #include <lib/cdev/CDev.hpp>
43 #include <perf/perf_counter.h>
44 #include <px4_platform_common/getopt.h>
45 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
46 #include <systemlib/err.h>
47 #include <uORB/uORB.h>
48 
49 
50 static constexpr uint8_t WHO_AM_I = 0x0F;
51 static constexpr uint8_t LPS22HB_ID_WHO_AM_I = 0xB1;
52 
53 static constexpr uint8_t CTRL_REG1 = 0x10;
54 static constexpr uint8_t CTRL_REG2 = 0x11;
55 static constexpr uint8_t CTRL_REG3 = 0x12;
56 
57 #define BOOT (1 << 7)
58 #define FIFO_EN (1 << 6)
59 #define STOP_ON_FTH (1 << 5)
60 #define IF_ADD_INC (1 << 4)
61 #define I2C_DIS (1 << 3)
62 #define SWRESET (1 << 2)
63 #define ONE_SHOT (1 << 0)
64 
65 static constexpr uint8_t STATUS = 0x27;
66 
67 #define T_OR (1 << 5) // Temperature data overrun.
68 #define P_OR (1 << 4) // Pressure data overrun.
69 #define T_DA (1 << 1) // Temperature data available.
70 #define P_DA (1 << 0) // Pressure data available.
71 
72 static constexpr uint8_t PRESS_OUT_XL = 0x28;
73 static constexpr uint8_t PRESS_OUT_L = 0x29;
74 static constexpr uint8_t PRESS_OUT_H = 0x2A;
75 
76 static constexpr uint8_t TEMP_OUT_L = 0x2B;
77 static constexpr uint8_t TEMP_OUT_H = 0x2C;
78 
79 /* interface factories */
80 extern device::Device *LPS22HB_SPI_interface(int bus);
81 extern device::Device *LPS22HB_I2C_interface(int bus);
82 typedef device::Device *(*LPS22HB_constructor)(int);
83 
84 class LPS22HB : public cdev::CDev, public px4::ScheduledWorkItem
85 {
86 public:
87  LPS22HB(device::Device *interface, const char *path);
88  virtual ~LPS22HB();
89 
90  virtual int init();
91 
92  virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
93 
94  /**
95  * Diagnostics - print some basic information about the driver.
96  */
97  void print_info();
98 
99 protected:
101 
102 private:
103  unsigned _measure_interval{0};
104 
105  bool _collect_phase{false};
106 
108 
111 
114 
115  sensor_baro_s _last_report{}; /**< used for info() */
116 
117  /**
118  * Initialise the automatic measurement state machine and start it.
119  *
120  * @note This function is called at open and error time. It might make sense
121  * to make it more aggressive about resetting the bus in case of errors.
122  */
123  void start();
124 
125  /**
126  * Stop the automatic measurement state machine.
127  */
128  void stop();
129 
130  /**
131  * Reset the device
132  */
133  int reset();
134 
135  /**
136  * Perform a poll cycle; collect from the previous measurement
137  * and start a new one.
138  *
139  * This is the heart of the measurement state machine. This function
140  * alternately starts a measurement, or collects the data from the
141  * previous measurement.
142  *
143  * When the interval between measurements is greater than the minimum
144  * measurement interval, a gap is inserted between collection
145  * and measurement to provide the most recent measurement possible
146  * at the next interval.
147  */
148  void Run() override;
149 
150  /**
151  * Write a register.
152  *
153  * @param reg The register to write.
154  * @param val The value to write.
155  * @return OK on write success.
156  */
157  int write_reg(uint8_t reg, uint8_t val);
158 
159  /**
160  * Read a register.
161  *
162  * @param reg The register to read.
163  * @param val The value read.
164  * @return OK on read success.
165  */
166  int read_reg(uint8_t reg, uint8_t &val);
167 
168  /**
169  * Issue a measurement command.
170  *
171  * @return OK if the measurement command was successful.
172  */
173  int measure();
174 
175  /**
176  * Collect the result of the most recent measurement.
177  */
178  int collect();
179 
180  /* this class has pointer data members, do not allow copying it */
181  LPS22HB(const LPS22HB &);
182  LPS22HB operator=(const LPS22HB &);
183 };
int reset()
Reset the device.
Definition: LPS22HB.cpp:184
static constexpr uint8_t LPS22HB_ID_WHO_AM_I
Definition: LPS22HB.hpp:51
bool _collect_phase
Definition: LPS22HB.hpp:105
int measure()
Issue a measurement command.
Definition: LPS22HB.cpp:235
API for the uORB lightweight object broker.
static constexpr uint8_t PRESS_OUT_XL
Definition: LPS22HB.hpp:72
static constexpr uint8_t TEMP_OUT_H
Definition: LPS22HB.hpp:77
unsigned _measure_interval
Definition: LPS22HB.hpp:103
device::Device * _interface
Definition: LPS22HB.hpp:100
static constexpr uint8_t PRESS_OUT_L
Definition: LPS22HB.hpp:73
void start()
Initialise the automatic measurement state machine and start it.
Definition: LPS22HB.cpp:168
sensor_baro_s _last_report
used for info()
Definition: LPS22HB.hpp:115
static constexpr uint8_t CTRL_REG2
Definition: LPS22HB.hpp:54
void Run() override
Perform a poll cycle; collect from the previous measurement and start a new one.
Definition: LPS22HB.cpp:194
perf_counter_t _sample_perf
Definition: LPS22HB.hpp:112
virtual ~LPS22HB()
Definition: LPS22HB.cpp:56
static constexpr uint8_t STATUS
Definition: LPS22HB.hpp:65
Definitions for the generic base classes in the device framework.
virtual int ioctl(struct file *filp, int cmd, unsigned long arg)
Definition: LPS22HB.cpp:100
orb_advert_t _baro_topic
Definition: LPS22HB.hpp:107
device::Device * LPS22HB_I2C_interface(int bus)
Definition: LPS22HB_I2C.cpp:61
Abstract class for any character device.
Definition: CDev.hpp:58
Header common to all counters.
static constexpr uint8_t TEMP_OUT_L
Definition: LPS22HB.hpp:76
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
static constexpr uint8_t CTRL_REG1
Definition: LPS22HB.hpp:53
perf_counter_t _comms_errors
Definition: LPS22HB.hpp:113
device::Device * LPS22HB_SPI_interface(int bus)
void print_info()
Diagnostics - print some basic information about the driver.
Definition: LPS22HB.cpp:327
static constexpr uint8_t CTRL_REG3
Definition: LPS22HB.hpp:55
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
int collect()
Collect the result of the most recent measurement.
Definition: LPS22HB.cpp:248
static constexpr uint8_t PRESS_OUT_H
Definition: LPS22HB.hpp:74
LPS22HB(device::Device *interface, const char *path)
Definition: LPS22HB.cpp:45
struct @83::@85::@87 file
int write_reg(uint8_t reg, uint8_t val)
Write a register.
Definition: LPS22HB.cpp:311
LPS22HB operator=(const LPS22HB &)
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
void stop()
Stop the automatic measurement state machine.
Definition: LPS22HB.cpp:178
int _class_instance
Definition: LPS22HB.hpp:110
virtual int init()
Definition: LPS22HB.cpp:73
Barometric pressure sensor driver interface.
static constexpr uint8_t WHO_AM_I
Definition: LPS22HB.hpp:50
int _orb_class_instance
Definition: LPS22HB.hpp:109
Performance measuring tools.
int read_reg(uint8_t reg, uint8_t &val)
Read a register.
Definition: LPS22HB.cpp:318
Base class for devices connected via I2C.