PX4 Firmware
PX4 Autopilot Software http://px4.io
ms5611.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2015 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 ms5611.cpp
36  * Driver for the MS5611 and MS5607 barometric pressure sensor connected via I2C or SPI.
37  */
38 
39 #include "MS5611.hpp"
40 #include "ms5611.h"
41 
42 #include <cdev/CDev.hpp>
43 
44 MS5611::MS5611(device::Device *interface, ms5611::prom_u &prom_buf, const char *path,
45  enum MS56XX_DEVICE_TYPES device_type) :
46  CDev(path),
47  ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())),
48  _interface(interface),
49  _prom(prom_buf.s),
50  _reports(nullptr),
51  _device_type(device_type),
52  _collect_phase(false),
53  _measure_phase(0),
54  _TEMP(0),
55  _OFF(0),
56  _SENS(0),
57  _baro_topic(nullptr),
58  _orb_class_instance(-1),
59  _class_instance(-1),
60  _sample_perf(perf_alloc(PC_ELAPSED, "ms5611_read")),
61  _measure_perf(perf_alloc(PC_ELAPSED, "ms5611_measure")),
62  _comms_errors(perf_alloc(PC_COUNT, "ms5611_com_err"))
63 {
64 }
65 
67 {
68  /* make sure we are truly inactive */
69  stop();
70 
71  if (_class_instance != -1) {
73  }
74 
75  /* free any existing reports */
76  if (_reports != nullptr) {
77  delete _reports;
78  }
79 
80  // free perf counters
84 
85  delete _interface;
86 }
87 
88 int
90 {
91  int ret;
92  bool autodetect = false;
93 
94  ret = CDev::init();
95 
96  if (ret != OK) {
97  PX4_DEBUG("CDev init failed");
98  goto out;
99  }
100 
101  /* allocate basic report buffers */
102  _reports = new ringbuffer::RingBuffer(2, sizeof(sensor_baro_s));
103 
104  if (_reports == nullptr) {
105  PX4_DEBUG("can't get memory for reports");
106  ret = -ENOMEM;
107  goto out;
108  }
109 
110  /* register alternate interfaces if we have to */
112 
113  sensor_baro_s brp;
114  /* do a first measurement cycle to populate reports with valid data */
115  _measure_phase = 0;
116  _reports->flush();
117 
118  if (_device_type == MS56XX_DEVICE) {
119  autodetect = true;
120  /* try first with MS5611 and fallback to MS5607 */
122  }
123 
124  while (true) {
125  /* do temperature first */
126  if (OK != measure()) {
127  ret = -EIO;
128  break;
129  }
130 
131  px4_usleep(MS5611_CONVERSION_INTERVAL);
132 
133  if (OK != collect()) {
134  ret = -EIO;
135  break;
136  }
137 
138  /* now do a pressure measurement */
139  if (OK != measure()) {
140  ret = -EIO;
141  break;
142  }
143 
144  px4_usleep(MS5611_CONVERSION_INTERVAL);
145 
146  if (OK != collect()) {
147  ret = -EIO;
148  break;
149  }
150 
151  /* state machine will have generated a report, copy it out */
152  _reports->get(&brp);
153 
154  if (autodetect) {
155  if (_device_type == MS5611_DEVICE) {
156  if (brp.pressure < 520.0f) {
157  /* This is likely not this device, try again */
159  _measure_phase = 0;
160 
161  continue;
162  }
163 
164  } else if (_device_type == MS5607_DEVICE) {
165  if (brp.pressure < 520.0f) {
166  /* Both devices returned a very low pressure;
167  * have fun on Everest using MS5611 */
169  }
170  }
171  }
172 
173  switch (_device_type) {
174  default:
175 
176  /* fall through */
177  case MS5611_DEVICE:
179  break;
180 
181  case MS5607_DEVICE:
183  break;
184  }
185 
186  /* ensure correct devid */
188 
189  ret = OK;
190 
191  _baro_topic = orb_advertise_multi(ORB_ID(sensor_baro), &brp,
193 
194  if (_baro_topic == nullptr) {
195  warnx("failed to create sensor_baro publication");
196  }
197 
198  break;
199  }
200 
201 out:
202  return ret;
203 }
204 
205 ssize_t
206 MS5611::read(cdev::file_t *filp, char *buffer, size_t buflen)
207 {
208  unsigned count = buflen / sizeof(sensor_baro_s);
209  sensor_baro_s *brp = reinterpret_cast<sensor_baro_s *>(buffer);
210  int ret = 0;
211 
212  /* buffer must be large enough */
213  if (count < 1) {
214  return -ENOSPC;
215  }
216 
217  /* if automatic measurement is enabled */
218  if (_measure_interval > 0) {
219 
220  /*
221  * While there is space in the caller's buffer, and reports, copy them.
222  * Note that we may be pre-empted by the workq thread while we are doing this;
223  * we are careful to avoid racing with them.
224  */
225  while (count--) {
226  if (_reports->get(brp)) {
227  ret += sizeof(*brp);
228  brp++;
229  }
230  }
231 
232  /* if there was no data, warn the caller */
233  return ret ? ret : -EAGAIN;
234  }
235 
236  /* manual measurement - run one conversion */
237  do {
238  _measure_phase = 0;
239  _reports->flush();
240 
241  /* do temperature first */
242  if (OK != measure()) {
243  ret = -EIO;
244  break;
245  }
246 
247  px4_usleep(MS5611_CONVERSION_INTERVAL);
248 
249  if (OK != collect()) {
250  ret = -EIO;
251  break;
252  }
253 
254  /* now do a pressure measurement */
255  if (OK != measure()) {
256  ret = -EIO;
257  break;
258  }
259 
260  px4_usleep(MS5611_CONVERSION_INTERVAL);
261 
262  if (OK != collect()) {
263  ret = -EIO;
264  break;
265  }
266 
267  /* state machine will have generated a report, copy it out */
268  if (_reports->get(brp)) {
269  ret = sizeof(*brp);
270  }
271 
272  } while (0);
273 
274  return ret;
275 }
276 
277 int
278 MS5611::ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
279 {
280  switch (cmd) {
281 
282  case SENSORIOCSPOLLRATE: {
283  switch (arg) {
284 
285  /* zero would be bad */
286  case 0:
287  return -EINVAL;
288 
289  /* set default polling rate */
291  /* do we need to start internal polling? */
292  bool want_start = (_measure_interval == 0);
293 
294  /* set interval for next measurement to minimum legal value */
296 
297  /* if we need to start the poll state machine, do it */
298  if (want_start) {
299  start();
300  }
301 
302  return OK;
303  }
304 
305  /* adjust to a legal polling interval in Hz */
306  default: {
307  /* do we need to start internal polling? */
308  bool want_start = (_measure_interval == 0);
309 
310  /* convert hz to interval via microseconds */
311  unsigned interval = (1000000 / arg);
312 
313  /* check against maximum rate */
315  return -EINVAL;
316  }
317 
318  /* update interval for next measurement */
319  _measure_interval = interval;
320 
321  /* if we need to start the poll state machine, do it */
322  if (want_start) {
323  start();
324  }
325 
326  return OK;
327  }
328  }
329  }
330 
331  case SENSORIOCRESET:
332  /*
333  * Since we are initialized, we do not need to do anything, since the
334  * PROM is correctly read and the part does not need to be configured.
335  */
336  return OK;
337 
338  default:
339  break;
340  }
341 
342  /* give it to the bus-specific superclass */
343  // return bus_ioctl(filp, cmd, arg);
344  return CDev::ioctl(filp, cmd, arg);
345 }
346 
347 void
349 {
350  /* reset the report ring and state machine */
351  _collect_phase = false;
352  _measure_phase = 0;
353  _reports->flush();
354 
355  /* schedule a cycle to start things */
356  ScheduleNow();
357 }
358 
359 void
361 {
362  ScheduleClear();
363 }
364 
365 void
367 {
368  int ret;
369  unsigned dummy;
370 
371  /* collection phase? */
372  if (_collect_phase) {
373 
374  /* perform collection */
375  ret = collect();
376 
377  if (ret != OK) {
378  if (ret == -6) {
379  /*
380  * The ms5611 seems to regularly fail to respond to
381  * its address; this happens often enough that we'd rather not
382  * spam the console with a message for this.
383  */
384  } else {
385  //DEVICE_LOG("collection error %d", ret);
386  }
387 
388  /* issue a reset command to the sensor */
389  _interface->ioctl(IOCTL_RESET, dummy);
390  /* reset the collection state machine and try again - we need
391  * to wait 2.8 ms after issuing the sensor reset command
392  * according to the MS5611 datasheet
393  */
394  ScheduleDelayed(2800);
395  return;
396  }
397 
398  /* next phase is measurement */
399  _collect_phase = false;
400 
401  /*
402  * Is there a collect->measure gap?
403  * Don't inject one after temperature measurements, so we can keep
404  * doing pressure measurements at something close to the desired rate.
405  */
406  if ((_measure_phase != 0) &&
408 
409  /* schedule a fresh cycle call when we are ready to measure again */
411 
412  return;
413  }
414  }
415 
416  /* measurement phase */
417  ret = measure();
418 
419  if (ret != OK) {
420  /* issue a reset command to the sensor */
421  _interface->ioctl(IOCTL_RESET, dummy);
422  /* reset the collection state machine and try again */
423  start();
424  return;
425  }
426 
427  /* next phase is collection */
428  _collect_phase = true;
429 
430  /* schedule a fresh cycle call when the measurement is done */
431  ScheduleDelayed(MS5611_CONVERSION_INTERVAL);
432 }
433 
434 int
436 {
437  int ret;
438 
440 
441  /*
442  * In phase zero, request temperature; in other phases, request pressure.
443  */
444  unsigned addr = (_measure_phase == 0) ? ADDR_CMD_CONVERT_D2 : ADDR_CMD_CONVERT_D1;
445 
446  /*
447  * Send the command to begin measuring.
448  */
449  ret = _interface->ioctl(IOCTL_MEASURE, addr);
450 
451  if (OK != ret) {
453  }
454 
456 
457  return ret;
458 }
459 
460 int
462 {
463  int ret;
464  uint32_t raw;
465 
467 
468  sensor_baro_s report;
469  /* this should be fairly close to the end of the conversion, so the best approximation of the time */
470  report.timestamp = hrt_absolute_time();
472 
473  /* read the most recent measurement - read offset/size are hardcoded in the interface */
474  ret = _interface->read(0, (void *)&raw, 0);
475 
476  if (ret < 0) {
479  return ret;
480  }
481 
482  /* handle a measurement */
483  if (_measure_phase == 0) {
484 
485  /* temperature offset (in ADC units) */
486  int32_t dT = (int32_t)raw - ((int32_t)_prom.c5_reference_temp << 8);
487 
488  /* absolute temperature in centidegrees - note intermediate value is outside 32-bit range */
489  _TEMP = 2000 + (int32_t)(((int64_t)dT * _prom.c6_temp_coeff_temp) >> 23);
490 
491  /* base sensor scale/offset values */
492  if (_device_type == MS5611_DEVICE) {
493 
494  /* Perform MS5611 Caculation */
495 
496  _OFF = ((int64_t)_prom.c2_pressure_offset << 16) + (((int64_t)_prom.c4_temp_coeff_pres_offset * dT) >> 7);
497  _SENS = ((int64_t)_prom.c1_pressure_sens << 15) + (((int64_t)_prom.c3_temp_coeff_pres_sens * dT) >> 8);
498 
499  /* MS5611 temperature compensation */
500 
501  if (_TEMP < 2000) {
502 
503  int32_t T2 = POW2(dT) >> 31;
504 
505  int64_t f = POW2((int64_t)_TEMP - 2000);
506  int64_t OFF2 = 5 * f >> 1;
507  int64_t SENS2 = 5 * f >> 2;
508 
509  if (_TEMP < -1500) {
510 
511  int64_t f2 = POW2(_TEMP + 1500);
512  OFF2 += 7 * f2;
513  SENS2 += 11 * f2 >> 1;
514  }
515 
516  _TEMP -= T2;
517  _OFF -= OFF2;
518  _SENS -= SENS2;
519  }
520 
521  } else if (_device_type == MS5607_DEVICE) {
522 
523  /* Perform MS5607 Caculation */
524 
525  _OFF = ((int64_t)_prom.c2_pressure_offset << 17) + (((int64_t)_prom.c4_temp_coeff_pres_offset * dT) >> 6);
526  _SENS = ((int64_t)_prom.c1_pressure_sens << 16) + (((int64_t)_prom.c3_temp_coeff_pres_sens * dT) >> 7);
527 
528  /* MS5607 temperature compensation */
529 
530  if (_TEMP < 2000) {
531 
532  int32_t T2 = POW2(dT) >> 31;
533 
534  int64_t f = POW2((int64_t)_TEMP - 2000);
535  int64_t OFF2 = 61 * f >> 4;
536  int64_t SENS2 = 2 * f;
537 
538  if (_TEMP < -1500) {
539  int64_t f2 = POW2(_TEMP + 1500);
540  OFF2 += 15 * f2;
541  SENS2 += 8 * f2;
542  }
543 
544  _TEMP -= T2;
545  _OFF -= OFF2;
546  _SENS -= SENS2;
547  }
548  }
549 
550  } else {
551 
552  /* pressure calculation, result in Pa */
553  int32_t P = (((raw * _SENS) >> 21) - _OFF) >> 15;
554  _P = P * 0.01f;
555  _T = _TEMP * 0.01f;
556 
557  /* generate a new report */
558  report.temperature = _TEMP / 100.0f;
559  report.pressure = P / 100.0f; /* convert to millibar */
560 
561  /* return device ID */
562  report.device_id = _interface->get_device_id();
563 
564  /* publish it */
565  if (_baro_topic != nullptr) {
566  /* publish it */
567  orb_publish(ORB_ID(sensor_baro), _baro_topic, &report);
568  }
569 
570  _reports->force(&report);
571 
572  /* notify anyone waiting for data */
573  poll_notify(POLLIN);
574  }
575 
576  /* update the measurement state machine */
578 
580 
581  return OK;
582 }
583 
584 void
586 {
589  printf("poll interval: %u\n", _measure_interval);
590  _reports->print_info("report queue");
591  printf("device: %s\n", _device_type == MS5611_DEVICE ? "ms5611" : "ms5607");
592 
593  sensor_baro_s brp = {};
594  _reports->get(&brp);
595  print_message(brp);
596 }
597 
598 /**
599  * Local functions in support of the shell command.
600  */
601 namespace ms5611
602 {
603 
604 /**
605  * MS5611 crc4 cribbed from the datasheet
606  */
607 bool
608 crc4(uint16_t *n_prom)
609 {
610  int16_t cnt;
611  uint16_t n_rem;
612  uint16_t crc_read;
613  uint8_t n_bit;
614 
615  n_rem = 0x00;
616 
617  /* save the read crc */
618  crc_read = n_prom[7];
619 
620  /* remove CRC byte */
621  n_prom[7] = (0xFF00 & (n_prom[7]));
622 
623  for (cnt = 0; cnt < 16; cnt++) {
624  /* uneven bytes */
625  if (cnt & 1) {
626  n_rem ^= (uint8_t)((n_prom[cnt >> 1]) & 0x00FF);
627 
628  } else {
629  n_rem ^= (uint8_t)(n_prom[cnt >> 1] >> 8);
630  }
631 
632  for (n_bit = 8; n_bit > 0; n_bit--) {
633  if (n_rem & 0x8000) {
634  n_rem = (n_rem << 1) ^ 0x3000;
635 
636  } else {
637  n_rem = (n_rem << 1);
638  }
639  }
640  }
641 
642  /* final 4 bit remainder is CRC value */
643  n_rem = (0x000F & (n_rem >> 12));
644  n_prom[7] = crc_read;
645 
646  /* return true if CRCs match */
647  return (0x000F & crc_read) == (n_rem ^ 0x00);
648 }
649 
650 } // namespace ms5611
int32_t _TEMP
Definition: MS5611.hpp:124
#define ADDR_CMD_CONVERT_D1
Definition: MS5611.hpp:82
int _class_instance
Definition: MS5611.hpp:132
ms5611::prom_s _prom
Definition: MS5611.hpp:114
#define MS5611_CONVERSION_INTERVAL
Definition: MS5611.hpp:90
~MS5611()
Definition: ms5611.cpp:66
uint16_t c1_pressure_sens
Definition: ms5611.h:74
bool crc4(uint16_t *n_prom)
MS5611 crc4 cribbed from the datasheet.
Definition: ms5611.cpp:608
perf_counter_t _measure_perf
Definition: MS5611.hpp:135
#define BARO_BASE_DEVICE_PATH
Definition: drv_baro.h:50
measure the time elapsed performing an event
Definition: perf_counter.h:56
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
virtual int register_class_devname(const char *class_devname)
Register a class device name, automatically adding device class instance suffix if need be...
Definition: CDev.cpp:78
perf_counter_t _comms_errors
Definition: MS5611.hpp:136
#define DRV_BARO_DEVTYPE_MS5611
Definition: drv_sensor.h:88
#define SENSOR_POLLRATE_DEFAULT
poll at driver normal rate
Definition: drv_sensor.h:136
orb_advert_t _baro_topic
Definition: MS5611.hpp:130
int _orb_class_instance
Definition: MS5611.hpp:131
uint64_t error_count
Definition: sensor_baro.h:54
uint32_t device_id
Definition: sensor_baro.h:55
count the number of times an event occurs
Definition: perf_counter.h:55
#define MS5611_MEASUREMENT_RATIO
Definition: MS5611.hpp:91
void start()
Initialize the automatic measurement state machine and start it.
Definition: ms5611.cpp:348
virtual void poll_notify(pollevent_t events)
Report new poll events.
Definition: CDev.cpp:330
uint32_t get_device_id() const
Definition: Device.hpp:161
#define SENSORIOCSPOLLRATE
Set the driver polling rate to (arg) Hz, or one of the SENSOR_POLLRATE constants. ...
Definition: drv_sensor.h:134
uint16_t c4_temp_coeff_pres_offset
Definition: ms5611.h:77
float temperature
Definition: sensor_baro.h:57
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
Shared defines for the ms5611 driver.
void perf_count(perf_counter_t handle)
Count a performance event.
float pressure
Definition: sensor_baro.h:56
void perf_free(perf_counter_t handle)
Free a counter.
void init()
Activates/configures the hardware registers.
device::Device * _interface
Definition: MS5611.hpp:112
uint16_t c5_reference_temp
Definition: ms5611.h:78
virtual int unregister_class_devname(const char *class_devname, unsigned class_instance)
Register a class device name, automatically adding device class instance suffix if need be...
Definition: CDev.cpp:109
#define perf_alloc(a, b)
Definition: px4io.h:59
#define POW2(_x)
Definition: mpl3115a2.cpp:52
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
#define warnx(...)
Definition: err.h:95
int64_t _SENS
Definition: MS5611.hpp:126
void perf_end(perf_counter_t handle)
End a performance event.
virtual int collect()
Collect the result of the most recent measurement.
Definition: ms5611.cpp:461
uint16_t c2_pressure_offset
Definition: ms5611.h:75
#define INCREMENT(_x, _lim)
Definition: mpl3115a2.cpp:49
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
Definition: uORB.cpp:70
uint16_t c6_temp_coeff_temp
Definition: ms5611.h:79
virtual int ioctl(unsigned operation, unsigned &arg)
Perform a device-specific operation.
Definition: Device.hpp:124
void set_device_type(uint8_t devtype)
Definition: Device.hpp:214
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
virtual bool external() const
Definition: Device.hpp:237
#define IOCTL_MEASURE
Definition: mpl3115a2.h:93
#define ADDR_CMD_CONVERT_D2
Definition: MS5611.hpp:83
const char * get_devname() const
Get the device name.
Definition: CDev.hpp:169
Grody hack for crc4()
Definition: ms5611.h:86
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
Local functions in support of the shell command.
Definition: ms5611.cpp:601
#define SENSORIOCRESET
Reset the sensor to its default configuration.
Definition: drv_sensor.h:141
uint64_t perf_event_count(perf_counter_t handle)
Return current event_count.
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
uint16_t c3_temp_coeff_pres_sens
Definition: ms5611.h:76
Definition: bst.cpp:62
virtual int init()
Definition: ms5611.cpp:89
unsigned _measure_phase
Definition: MS5611.hpp:121
ringbuffer::RingBuffer * _reports
Definition: MS5611.hpp:118
#define OK
Definition: uavcan_main.cpp:71
virtual int ioctl(cdev::file_t *filp, int cmd, unsigned long arg)
Perform an ioctl operation on the device.
Definition: ms5611.cpp:278
uint64_t timestamp
Definition: sensor_baro.h:53
P[0][0]
Definition: quatCovMat.c:44
MS56XX_DEVICE_TYPES
Definition: MS5611.hpp:50
enum MS56XX_DEVICE_TYPES _device_type
Definition: MS5611.hpp:119
void print_info()
Diagnostics - print some basic information about the driver.
Definition: ms5611.cpp:585
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority)
Definition: uORB.cpp:53
unsigned _measure_interval
Definition: MS5611.hpp:116
void perf_begin(perf_counter_t handle)
Begin a performance event.
#define DRV_BARO_DEVTYPE_MS5607
Definition: drv_sensor.h:89
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
virtual int read(unsigned address, void *data, unsigned count)
Read directly from the device.
Definition: Device.hpp:103
#define IOCTL_RESET
Definition: mpl3115a2.h:92
float _P
Definition: MS5611.hpp:127