PX4 Firmware
PX4 Autopilot Software http://px4.io
MS5611.hpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-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 #pragma once
35 
36 #include <drivers/device/i2c.h>
37 #include <drivers/device/device.h>
39 #include <drivers/device/spi.h>
40 #include <drivers/drv_baro.h>
41 #include <lib/cdev/CDev.hpp>
42 #include <lib/perf/perf_counter.h>
43 #include <px4_platform_common/getopt.h>
44 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
45 #include <systemlib/err.h>
46 #include <uORB/uORB.h>
47 
48 #include "ms5611.h"
49 
52  MS5611_DEVICE = 5611,
53  MS5607_DEVICE = 5607,
54 };
55 
56 /* helper macro for handling report buffer indices */
57 #define INCREMENT(_x, _lim) do { __typeof__(_x) _tmp = _x+1; if (_tmp >= _lim) _tmp = 0; _x = _tmp; } while(0)
58 
59 /* helper macro for arithmetic - returns the square of the argument */
60 #define POW2(_x) ((_x) * (_x))
61 
62 /*
63  * MS5611/MS5607 internal constants and data structures.
64  */
65 #define ADDR_CMD_CONVERT_D1_OSR256 0x40 /* write to this address to start pressure conversion */
66 #define ADDR_CMD_CONVERT_D1_OSR512 0x42 /* write to this address to start pressure conversion */
67 #define ADDR_CMD_CONVERT_D1_OSR1024 0x44 /* write to this address to start pressure conversion */
68 #define ADDR_CMD_CONVERT_D1_OSR2048 0x46 /* write to this address to start pressure conversion */
69 #define ADDR_CMD_CONVERT_D1_OSR4096 0x48 /* write to this address to start pressure conversion */
70 #define ADDR_CMD_CONVERT_D2_OSR256 0x50 /* write to this address to start temperature conversion */
71 #define ADDR_CMD_CONVERT_D2_OSR512 0x52 /* write to this address to start temperature conversion */
72 #define ADDR_CMD_CONVERT_D2_OSR1024 0x54 /* write to this address to start temperature conversion */
73 #define ADDR_CMD_CONVERT_D2_OSR2048 0x56 /* write to this address to start temperature conversion */
74 #define ADDR_CMD_CONVERT_D2_OSR4096 0x58 /* write to this address to start temperature conversion */
75 
76 /*
77  use an OSR of 1024 to reduce the self-heating effect of the
78  sensor. Information from MS tells us that some individual sensors
79  are quite sensitive to this effect and that reducing the OSR can
80  make a big difference
81  */
82 #define ADDR_CMD_CONVERT_D1 ADDR_CMD_CONVERT_D1_OSR1024
83 #define ADDR_CMD_CONVERT_D2 ADDR_CMD_CONVERT_D2_OSR1024
84 
85 /*
86  * Maximum internal conversion time for OSR 1024 is 2.28 ms. We set an update
87  * rate of 100Hz which is be very safe not to read the ADC before the
88  * conversion finished
89  */
90 #define MS5611_CONVERSION_INTERVAL 10000 /* microseconds */
91 #define MS5611_MEASUREMENT_RATIO 3 /* pressure measurements per temperature measurement */
92 #define MS5611_BARO_DEVICE_PATH_EXT "/dev/ms5611_ext"
93 #define MS5611_BARO_DEVICE_PATH_INT "/dev/ms5611_int"
94 
95 class MS5611 : public cdev::CDev, public px4::ScheduledWorkItem
96 {
97 public:
98  MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char *path, enum MS56XX_DEVICE_TYPES device_type);
99  ~MS5611();
100 
101  virtual int init();
102 
103  virtual ssize_t read(cdev::file_t *filp, char *buffer, size_t buflen);
104  virtual int ioctl(cdev::file_t *filp, int cmd, unsigned long arg);
105 
106  /**
107  * Diagnostics - print some basic information about the driver.
108  */
109  void print_info();
110 
111 protected:
113 
115 
116  unsigned _measure_interval{0};
117 
118  ringbuffer::RingBuffer *_reports;
121  unsigned _measure_phase;
122 
123  /* intermediate temperature values per MS5611/MS5607 datasheet */
124  int32_t _TEMP;
125  int64_t _OFF;
126  int64_t _SENS;
127  float _P;
128  float _T;
129 
133 
137 
138  /**
139  * Initialize the automatic measurement state machine and start it.
140  *
141  * @note This function is called at open and error time. It might make sense
142  * to make it more aggressive about resetting the bus in case of errors.
143  */
144  void start();
145 
146  /**
147  * Stop the automatic measurement state machine.
148  */
149  void stop();
150 
151  /**
152  * Perform a poll cycle; collect from the previous measurement
153  * and start a new one.
154  *
155  * This is the heart of the measurement state machine. This function
156  * alternately starts a measurement, or collects the data from the
157  * previous measurement.
158  *
159  * When the interval between measurements is greater than the minimum
160  * measurement interval, a gap is inserted between collection
161  * and measurement to provide the most recent measurement possible
162  * at the next interval.
163  */
164  void Run() override;
165 
166  /**
167  * Issue a measurement command for the current state.
168  *
169  * @return OK if the measurement command was successful.
170  */
171  virtual int measure();
172 
173  /**
174  * Collect the result of the most recent measurement.
175  */
176  virtual int collect();
177 };
int32_t _TEMP
Definition: MS5611.hpp:124
int _class_instance
Definition: MS5611.hpp:132
ms5611::prom_s _prom
Definition: MS5611.hpp:114
~MS5611()
Definition: ms5611.cpp:66
perf_counter_t _measure_perf
Definition: MS5611.hpp:135
API for the uORB lightweight object broker.
virtual ssize_t read(cdev::file_t *filp, char *buffer, size_t buflen)
Perform a read from the device.
Definition: ms5611.cpp:206
MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char *path, enum MS56XX_DEVICE_TYPES device_type)
Definition: ms5611.cpp:44
perf_counter_t _sample_perf
Definition: MS5611.hpp:134
perf_counter_t _comms_errors
Definition: MS5611.hpp:136
orb_advert_t _baro_topic
Definition: MS5611.hpp:130
int _orb_class_instance
Definition: MS5611.hpp:131
Calibration PROM as reported by the device.
Definition: ms5611.h:72
void start()
Initialize the automatic measurement state machine and start it.
Definition: ms5611.cpp:348
Shared defines for the ms5611 driver.
Abstract class for any character device.
Definition: CDev.hpp:58
Header common to all counters.
device::Device * _interface
Definition: MS5611.hpp:112
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
int64_t _SENS
Definition: MS5611.hpp:126
virtual int collect()
Collect the result of the most recent measurement.
Definition: ms5611.cpp:461
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
float _T
Definition: MS5611.hpp:128
void stop()
Stop the automatic measurement state machine.
Definition: ms5611.cpp:360
void Run() override
Perform a poll cycle; collect from the previous measurement and start a new one.
Definition: ms5611.cpp:366
Grody hack for crc4()
Definition: ms5611.h:86
bool _collect_phase
Definition: MS5611.hpp:120
int64_t _OFF
Definition: MS5611.hpp:125
virtual int measure()
Issue a measurement command for the current state.
Definition: ms5611.cpp:435
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
virtual int init()
Definition: ms5611.cpp:89
unsigned _measure_phase
Definition: MS5611.hpp:121
ringbuffer::RingBuffer * _reports
Definition: MS5611.hpp:118
virtual int ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
Perform an ioctl operation on the device.
Definition: ms5611.cpp:278
MS56XX_DEVICE_TYPES
Definition: MS5611.hpp:50
enum MS56XX_DEVICE_TYPES _device_type
Definition: MS5611.hpp:119
Barometric pressure sensor driver interface.
void print_info()
Diagnostics - print some basic information about the driver.
Definition: ms5611.cpp:585
unsigned _measure_interval
Definition: MS5611.hpp:116
Performance measuring tools.
float _P
Definition: MS5611.hpp:127
Base class for devices connected via I2C.