PX4 Firmware
PX4 Autopilot Software http://px4.io
mpl3115a2.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2017-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 /**
35  * @file mpl3115a2.cpp
36  *
37  * Driver for the MPL3115A2 barometric pressure sensor connected via I2C.
38  */
39 
40 #include "mpl3115a2.h"
41 
46 };
47 
48 /* helper macro for handling report buffer indices */
49 #define INCREMENT(_x, _lim) do { __typeof__(_x) _tmp = _x+1; if (_tmp >= _lim) _tmp = 0; _x = _tmp; } while(0)
50 
51 /* helper macro for arithmetic - returns the square of the argument */
52 #define POW2(_x) ((_x) * (_x))
53 
54 /*
55  * MPL3115A2 internal constants and data structures.
56  */
57 
58 #define MPL3115A2_CONVERSION_INTERVAL 10000 /* microseconds */
59 #define MPL3115A2_OSR 2 /* Over Sample rate of 4 18MS Minimum time between data samples */
60 #define MPL3115A2_CTRL_TRIGGER (CTRL_REG1_OST | CTRL_REG1_OS(MPL3115A2_OSR))
61 #define MPL3115A2_BARO_DEVICE_PATH_EXT "/dev/mpl3115a2_ext"
62 #define MPL3115A2_BARO_DEVICE_PATH_INT "/dev/mpl3115a2_int"
63 
64 class MPL3115A2 : public cdev::CDev, public px4::ScheduledWorkItem
65 {
66 public:
67  MPL3115A2(device::Device *interface, const char *path);
68  ~MPL3115A2();
69 
70  virtual int init();
71 
72  virtual ssize_t read(struct file *filp, char *buffer, size_t buflen);
73  virtual int ioctl(struct file *filp, int cmd, unsigned long arg);
74 
75  /**
76  * Diagnostics - print some basic information about the driver.
77  */
78  void print_info();
79 
80 protected:
82 
84 
85  ringbuffer::RingBuffer *_reports;
87 
88  /* */
89  float _P;
90  float _T;
91 
95 
99 
100  /**
101  * Initialize the automatic measurement state machine and start it.
102  *
103  * @param delay_us the number of microseconds before executing the next cycle
104  *
105  * @note This function is called at open and error time. It might make sense
106  * to make it more aggressive about resetting the bus in case of errors.
107  */
108  void start(unsigned delay_us = 1);
109 
110  /**
111  * Stop the automatic measurement state machine.
112  */
113  void stop();
114 
115  /**
116  * Perform a poll cycle; collect from the previous measurement
117  * and start a new one.
118  *
119  * This is the heart of the measurement state machine. This function
120  * alternately starts a measurement, or collects the data from the
121  * previous measurement.
122  *
123  * When the interval between measurements is greater than the minimum
124  * measurement interval, a gap is inserted between collection
125  * and measurement to provide the most recent measurement possible
126  * at the next interval.
127  */
128  void Run() override;
129 
130  /**
131  * Issue a measurement command for the current state.
132  *
133  * @return OK if the measurement command was successful.
134  */
135  virtual int measure();
136 
137  /**
138  * Collect the result of the most recent measurement.
139  */
140  virtual int collect();
141 
142 };
143 
144 /*
145  * Driver 'main' command.
146  */
147 extern "C" __EXPORT int mpl3115a2_main(int argc, char *argv[]);
148 
149 MPL3115A2::MPL3115A2(device::Device *interface, const char *path) :
150  CDev(path),
151  ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id())),
152  _interface(interface),
154  _reports(nullptr),
155  _collect_phase(false),
156  _P(0),
157  _T(0),
158  _baro_topic(nullptr),
160  _class_instance(-1),
161  _sample_perf(perf_alloc(PC_ELAPSED, "mpl3115a2_read")),
162  _measure_perf(perf_alloc(PC_ELAPSED, "mpl3115a2_measure")),
163  _comms_errors(perf_alloc(PC_COUNT, "mpl3115a2_com_err"))
164 {
166 }
167 
169 {
170  /* make sure we are truly inactive */
171  stop();
172 
173  if (_class_instance != -1) {
175  }
176 
177  /* free any existing reports */
178  if (_reports != nullptr) {
179  delete _reports;
180  }
181 
182  // free perf counters
186 
187  delete _interface;
188 }
189 
190 int
192 {
193  int ret;
194 
195  ret = CDev::init();
196 
197  if (ret != OK) {
198  PX4_DEBUG("CDev init failed");
199  goto out;
200  }
201 
202  /* allocate basic report buffers */
203  _reports = new ringbuffer::RingBuffer(2, sizeof(sensor_baro_s));
204 
205  if (_reports == nullptr) {
206  PX4_DEBUG("can't get memory for reports");
207  ret = -ENOMEM;
208  goto out;
209  }
210 
211  /* register alternate interfaces if we have to */
213 
214  sensor_baro_s brp;
215  _reports->flush();
216 
217  while (true) {
218 
219  /* First reading */
220  do {
221  ret = measure();
222 
223  if (ret == -EAGAIN) {
224  usleep(500);
225  }
226  } while (ret == -EAGAIN);
227 
228  if (ret != OK) {
229  ret = -EIO;
230  break;
231  }
232 
233  /* First reading */
234  do {
235  ret = collect();
236 
237  if (ret == -EAGAIN) {
238  usleep(500);
239  }
240  } while (ret == -EAGAIN);
241 
242  if (ret != OK) {
243  ret = -EIO;
244  break;
245  }
246 
247  /* state machine will have generated a report, copy it out */
248  _reports->get(&brp);
249 
250  // DEVICE_LOG("altitude (%u) = %.2f", _device_type, (double)brp.altitude);
251 
252  /* ensure correct devid */
254 
255  ret = OK;
256 
257  _baro_topic = orb_advertise_multi(ORB_ID(sensor_baro), &brp,
259 
260  if (_baro_topic == nullptr) {
261  warnx("failed to create sensor_baro publication");
262  }
263 
264  break;
265  }
266 
267 out:
268  return ret;
269 }
270 
271 ssize_t
272 MPL3115A2::read(struct file *filp, char *buffer, size_t buflen)
273 {
274  unsigned count = buflen / sizeof(sensor_baro_s);
275  sensor_baro_s *brp = reinterpret_cast<sensor_baro_s *>(buffer);
276  int ret = 0;
277 
278  /* buffer must be large enough */
279  if (count < 1) {
280  return -ENOSPC;
281  }
282 
283  /* if automatic measurement is enabled */
284  if (_measure_interval > 0) {
285 
286  /*
287  * While there is space in the caller's buffer, and reports, copy them.
288  * Note that we may be pre-empted by the workq thread while we are doing this;
289  * we are careful to avoid racing with them.
290  */
291  while (count--) {
292  if (_reports->get(brp)) {
293  ret += sizeof(*brp);
294  brp++;
295  }
296  }
297 
298  /* if there was no data, warn the caller */
299  return ret ? ret : -EAGAIN;
300  }
301 
302  /* manual measurement - run one conversion */
303  do {
304  _reports->flush();
305 
306  /* First reading */
307  do {
308  ret = measure();
309 
310  if (ret == -EAGAIN) {
311  usleep(1000);
312  }
313  } while (ret == -EAGAIN);
314 
315  if (ret != OK) {
316  ret = -EIO;
317  break;
318  }
319 
320  if (OK != collect()) {
321  ret = -EIO;
322  break;
323  }
324 
325  /* state machine will have generated a report, copy it out */
326  if (_reports->get(brp)) {
327  ret = sizeof(*brp);
328  }
329 
330  } while (0);
331 
332  return ret;
333 }
334 
335 int
336 MPL3115A2::ioctl(struct file *filp, int cmd, unsigned long arg)
337 {
338  switch (cmd) {
339 
340  case SENSORIOCSPOLLRATE: {
341  switch (arg) {
342 
343  /* zero would be bad */
344  case 0:
345  return -EINVAL;
346 
347  /* set default polling rate */
349  /* do we need to start internal polling? */
350  bool want_start = (_measure_interval == 0);
351 
352  /* set interval for next measurement to minimum legal value */
354 
355  /* if we need to start the poll state machine, do it */
356  if (want_start) {
357  start();
358  }
359 
360  return OK;
361  }
362 
363  /* adjust to a legal polling interval in Hz */
364  default: {
365  /* do we need to start internal polling? */
366  bool want_start = (_measure_interval == 0);
367 
368  /* convert hz to tick interval via microseconds */
369  unsigned interval = (1000000 / arg);
370 
371  /* check against maximum rate */
372  if (interval < MPL3115A2_CONVERSION_INTERVAL) {
373  return -EINVAL;
374  }
375 
376  /* update interval for next measurement */
377  _measure_interval = interval;
378 
379  /* if we need to start the poll state machine, do it */
380  if (want_start) {
381  start();
382  }
383 
384  return OK;
385  }
386  }
387  }
388 
389  case SENSORIOCRESET: {
390  /*
391  * Since we are initialized, we do not need to do anything, since the
392  * PROM is correctly read and the part does not need to be configured.
393  */
394  unsigned int dummy;
395  _interface->ioctl(IOCTL_RESET, dummy);
396  return OK;
397  }
398 
399  default:
400  break;
401  }
402 
403  /* give it to the bus-specific superclass */
404  // return bus_ioctl(filp, cmd, arg);
405  return CDev::ioctl(filp, cmd, arg);
406 }
407 
408 void
409 MPL3115A2::start(unsigned delay_us)
410 {
411  /* reset the report ring and state machine */
412  _collect_phase = false;
413  _reports->flush();
414 
415  /* schedule a cycle to start things */
416  ScheduleDelayed(delay_us);
417 }
418 
419 void
421 {
422  ScheduleClear();
423 }
424 
425 void
427 {
428  int ret;
429  unsigned dummy;
430 
431  /* collection phase? */
432  if (_collect_phase) {
433 
434  /* perform collection */
435  ret = collect();
436 
437  if (ret == -EIO) {
438  /* issue a reset command to the sensor */
439  _interface->ioctl(IOCTL_RESET, dummy);
440  /* reset the collection state machine and try again - we need
441  * to wait 2.8 ms after issuing the sensor reset command
442  * according to the MPL3115A2 datasheet
443  */
444  start(2800);
445  return;
446  }
447 
448  if (ret == -EAGAIN) {
449 
450  /* Ready read it on next cycle */
451  ScheduleDelayed(MPL3115A2_CONVERSION_INTERVAL);
452 
453  return;
454  }
455 
456  /* next phase is measurement */
457  _collect_phase = false;
458  }
459 
460  /* Look for a ready condition */
461 
462  ret = measure();
463 
464  if (ret == -EIO) {
465  /* issue a reset command to the sensor */
466  _interface->ioctl(IOCTL_RESET, dummy);
467  /* reset the collection state machine and try again */
468  start();
469  return;
470  }
471 
472  /* next phase is measurement */
473  _collect_phase = true;
474 
475  /* schedule a fresh cycle call when the measurement is done */
476  ScheduleDelayed(MPL3115A2_CONVERSION_INTERVAL);
477 }
478 
479 int
481 {
482  int ret;
483 
485 
486  /*
487  * Send the command to read the ADC for P and T.
488  */
489  unsigned addr = (MPL3115A2_CTRL_REG1 << 8) | MPL3115A2_CTRL_TRIGGER;
490  ret = _interface->ioctl(IOCTL_MEASURE, addr);
491 
492  if (ret == -EIO) {
494  }
495 
497 
498  return PX4_OK;
499 }
500 
501 int
503 {
504  int ret;
505  MPL3115A2_data_t reading;
506  uint8_t ctrl;
507 
509 
510  ret = _interface->read(MPL3115A2_CTRL_REG1, (void *)&ctrl, 1);
511 
512  if (ret == -EIO) {
514  return ret;
515  }
516 
517  if (ctrl & CTRL_REG1_OST) {
519  return -EAGAIN;
520  }
521 
522  sensor_baro_s report;
523 
524  /* this should be fairly close to the end of the conversion, so the best approximation of the time */
525  report.timestamp = hrt_absolute_time();
526 
528 
529  /* read the most recent measurement - read offset/size are hardcoded in the interface */
530  ret = _interface->read(OUT_P_MSB, (void *)&reading, sizeof(reading));
531 
532  if (ret == -EIO) {
535  return ret;
536  }
537 
538  _T = (float) reading.temperature.b[1] + ((float)(reading.temperature.b[0]) / 16.0f);
539  _P = (float)(reading.pressure.q >> 8) + ((float)(reading.pressure.b[0]) / 4.0f);
540 
541  report.temperature = _T;
542  report.pressure = _P / 100.0f; /* convert to millibar */
543 
544  /* return device ID */
545  report.device_id = _interface->get_device_id();
546 
547  /* publish it */
548  if (_baro_topic != nullptr) {
549  /* publish it */
550  orb_publish(ORB_ID(sensor_baro), _baro_topic, &report);
551  }
552 
553  _reports->force(&report);
554 
555  /* notify anyone waiting for data */
556  poll_notify(POLLIN);
557 
559 
560  return OK;
561 }
562 
563 void
565 {
568  printf("poll interval: %u\n", _measure_interval);
569  _reports->print_info("report queue");
570 
571  sensor_baro_s brp = {};
572  _reports->get(&brp);
573  print_message(brp);
574 }
575 
576 /**
577  * Local functions in support of the shell command.
578  */
579 namespace mpl3115a2
580 {
581 
582 /*
583  list of supported bus configurations
584  */
586  enum MPL3115A2_BUS busid;
587  const char *devpath;
589  uint8_t busnum;
591 } bus_options[] = {
592 #if defined(PX4_SPIDEV_EXT_BARO) && defined(PX4_SPI_BUS_EXT)
593  { MPL3115A2_BUS_SPI_EXTERNAL, "/dev/mpl3115a2_spi_ext", &MPL3115A2_spi_interface, PX4_SPI_BUS_EXT, NULL },
594 #endif
595 #ifdef PX4_SPIDEV_BARO
596  { MPL3115A2_BUS_SPI_INTERNAL, "/dev/mpl3115a2_spi_int", &MPL3115A2_spi_interface, PX4_SPI_BUS_BARO, NULL },
597 #endif
598 #ifdef PX4_I2C_BUS_ONBOARD
599  { MPL3115A2_BUS_I2C_INTERNAL, "/dev/mpl3115a2_int", &MPL3115A2_i2c_interface, PX4_I2C_BUS_ONBOARD, NULL },
600 #endif
601 #ifdef PX4_I2C_BUS_EXPANSION
602  { MPL3115A2_BUS_I2C_EXTERNAL, "/dev/mpl3115a2_ext", &MPL3115A2_i2c_interface, PX4_I2C_BUS_EXPANSION, NULL },
603 #endif
604 #ifdef PX4_I2C_BUS_EXPANSION1
605  { MPL3115A2_BUS_I2C_EXTERNAL, "/dev/mpl3115a2_ext1", &MPL3115A2_i2c_interface, PX4_I2C_BUS_EXPANSION1, NULL },
606 #endif
607 #ifdef PX4_I2C_BUS_EXPANSION2
608  { MPL3115A2_BUS_I2C_EXTERNAL, "/dev/mpl3115a2_ext2", &MPL3115A2_i2c_interface, PX4_I2C_BUS_EXPANSION2, NULL },
609 #endif
610 };
611 #define NUM_BUS_OPTIONS (sizeof(bus_options)/sizeof(bus_options[0]))
612 
613 bool start_bus(struct mpl3115a2_bus_option &bus);
614 struct mpl3115a2_bus_option &find_bus(enum MPL3115A2_BUS busid);
615 void start(enum MPL3115A2_BUS busid);
616 void test(enum MPL3115A2_BUS busid);
617 void reset(enum MPL3115A2_BUS busid);
618 void info();
619 void usage();
620 
621 /**
622  * Start the driver.
623  */
624 bool
626 {
627  if (bus.dev != nullptr) {
628  errx(1, "bus option already started");
629  }
630 
631  device::Device *interface = bus.interface_constructor(bus.busnum);
632 
633  if (interface->init() != OK) {
634  delete interface;
635  warnx("no device on bus %u", (unsigned)bus.busid);
636  return false;
637  }
638 
639  bus.dev = new MPL3115A2(interface, bus.devpath);
640 
641  if (bus.dev != nullptr && OK != bus.dev->init()) {
642  delete bus.dev;
643  bus.dev = NULL;
644  return false;
645  }
646 
647  int fd = open(bus.devpath, O_RDONLY);
648 
649  /* set the poll rate to default, starts automatic data collection */
650  if (fd == -1) {
651  errx(1, "can't open baro device");
652  }
653 
655  close(fd);
656  errx(1, "failed setting default poll rate");
657  }
658 
659  close(fd);
660  return true;
661 }
662 
663 
664 /**
665  * Start the driver.
666  *
667  * This function call only returns once the driver
668  * is either successfully up and running or failed to start.
669  */
670 void
671 start(enum MPL3115A2_BUS busid)
672 {
673  uint8_t i;
674  bool started = false;
675 
676  for (i = 0; i < NUM_BUS_OPTIONS; i++) {
677  if (busid == MPL3115A2_BUS_ALL && bus_options[i].dev != NULL) {
678  // this device is already started
679  continue;
680  }
681 
682  if (busid != MPL3115A2_BUS_ALL && bus_options[i].busid != busid) {
683  // not the one that is asked for
684  continue;
685  }
686 
687  started = started | start_bus(bus_options[i]);
688  }
689 
690  if (!started) {
691  exit(1);
692  }
693 
694  // one or more drivers started OK
695  exit(0);
696 }
697 
698 
699 /**
700  * find a bus structure for a busid
701  */
703 {
704  for (uint8_t i = 0; i < NUM_BUS_OPTIONS; i++) {
705  if ((busid == MPL3115A2_BUS_ALL ||
706  busid == bus_options[i].busid) && bus_options[i].dev != NULL) {
707  return bus_options[i];
708  }
709  }
710 
711  errx(1, "bus %u not started", (unsigned)busid);
712 }
713 
714 /**
715  * Perform some basic functional tests on the driver;
716  * make sure we can collect data from the sensor in polled
717  * and automatic modes.
718  */
719 void
720 test(enum MPL3115A2_BUS busid)
721 {
722  struct mpl3115a2_bus_option &bus = find_bus(busid);
723  sensor_baro_s report;
724  ssize_t sz;
725  int ret;
726 
727  int fd;
728 
729  fd = open(bus.devpath, O_RDONLY);
730 
731  if (fd < 0) {
732  err(1, "open failed (try 'mpl3115a2 start' if the driver is not running)");
733  }
734 
735  /* do a simple demand read */
736  sz = read(fd, &report, sizeof(report));
737 
738  if (sz != sizeof(report)) {
739  err(1, "immediate read failed");
740  }
741 
742  print_message(report);
743 
744  /* read the sensor 5x and report each value */
745  for (unsigned i = 0; i < 5; i++) {
746  struct pollfd fds;
747 
748  /* wait for data to be ready */
749  fds.fd = fd;
750  fds.events = POLLIN;
751  ret = poll(&fds, 1, 2000);
752 
753  if (ret != 1) {
754  errx(1, "timed out waiting for sensor data");
755  }
756 
757  /* now go get it */
758  sz = read(fd, &report, sizeof(report));
759 
760  if (sz != sizeof(report)) {
761  err(1, "periodic read failed");
762  }
763 
764  print_message(report);
765  }
766 
767  close(fd);
768  errx(0, "PASS");
769 }
770 
771 /**
772  * Reset the driver.
773  */
774 void
775 reset(enum MPL3115A2_BUS busid)
776 {
777  struct mpl3115a2_bus_option &bus = find_bus(busid);
778  int fd;
779 
780  fd = open(bus.devpath, O_RDONLY);
781 
782  if (fd < 0) {
783  err(1, "failed ");
784  }
785 
786  if (ioctl(fd, SENSORIOCRESET, 0) < 0) {
787  err(1, "driver reset failed");
788  }
789 
791  err(1, "driver poll restart failed");
792  }
793 
794  exit(0);
795 }
796 
797 /**
798  * Print a little info about the driver.
799  */
800 void
802 {
803  for (uint8_t i = 0; i < NUM_BUS_OPTIONS; i++) {
804  struct mpl3115a2_bus_option &bus = bus_options[i];
805 
806  if (bus.dev != nullptr) {
807  warnx("%s", bus.devpath);
808  bus.dev->print_info();
809  }
810  }
811 
812  exit(0);
813 }
814 
815 void
817 {
818  warnx("missing command: try 'start', 'info', 'test', 'reset'");
819  warnx("options:");
820  warnx(" -X (external I2C bus)");
821  warnx(" -I (intternal I2C bus)");
822 
823 }
824 
825 } // namespace
826 
827 int
828 mpl3115a2_main(int argc, char *argv[])
829 {
830  enum MPL3115A2_BUS busid = MPL3115A2_BUS_ALL;
831  int myoptind = 1;
832  int ch;
833  const char *myoptarg = NULL;
834 
835  /* jump over start/off/etc and look at options first */
836  while ((ch = px4_getopt(argc, argv, "XI", &myoptind, &myoptarg)) != EOF) {
837  switch (ch) {
838  case 'X':
840  break;
841 
842  case 'I':
844  break;
845 
846  default:
848  exit(0);
849  }
850  }
851 
852  if (myoptind >= argc) {
854  exit(0);
855  }
856 
857  const char *verb = argv[myoptind];
858 
859  /*
860  * Start/load the driver.
861  */
862  if (!strcmp(verb, "start")) {
863  mpl3115a2::start(busid);
864  }
865 
866  /*
867  * Test the driver/device.
868  */
869  if (!strcmp(verb, "test")) {
870  mpl3115a2::test(busid);
871  }
872 
873  /*
874  * Reset the driver.
875  */
876  if (!strcmp(verb, "reset")) {
877  mpl3115a2::reset(busid);
878  }
879 
880  /*
881  * Print driver information.
882  */
883  if (!strcmp(verb, "info")) {
884  mpl3115a2::info();
885  }
886 
888  exit(1);
889 }
int _orb_class_instance
Definition: mpl3115a2.cpp:93
device::Device *(* MPL3115A2_constructor)(uint8_t busnum)
Definition: mpl3115a2.h:111
virtual int init()
Definition: mpl3115a2.cpp:191
unsigned _measure_interval
Definition: mpl3115a2.cpp:83
virtual int open(file_t *filep)
Handle an open of the device.
Definition: CDev.cpp:141
#define BARO_BASE_DEVICE_PATH
Definition: drv_baro.h:50
measure the time elapsed performing an event
Definition: perf_counter.h:56
float _P
Definition: mpl3115a2.cpp:89
void info()
Print a little info about the driver.
Definition: mpl3115a2.cpp:801
orb_advert_t _baro_topic
Definition: mpl3115a2.cpp:92
virtual int measure()
Issue a measurement command for the current state.
Definition: mpl3115a2.cpp:480
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
Shared defines for the mpl3115a2 driver.
#define SENSOR_POLLRATE_DEFAULT
poll at driver normal rate
Definition: drv_sensor.h:136
void usage(const char *reason)
Print the correct usage.
Definition: Commander.cpp:4238
MPL3115A2_constructor interface_constructor
Definition: mpl3115a2.cpp:588
__EXPORT int mpl3115a2_main(int argc, char *argv[])
Definition: mpl3115a2.cpp:828
Definition: I2C.hpp:51
perf_counter_t _comms_errors
Definition: mpl3115a2.cpp:98
uint64_t error_count
Definition: sensor_baro.h:54
virtual ssize_t read(struct file *filp, char *buffer, size_t buflen)
Definition: mpl3115a2.cpp:272
void usage()
Prints info about the driver argument usage.
Definition: mpl3115a2.cpp:816
int _class_instance
Definition: mpl3115a2.cpp:94
uint32_t device_id
Definition: sensor_baro.h:55
count the number of times an event occurs
Definition: perf_counter.h:55
ringbuffer::RingBuffer * _reports
Definition: mpl3115a2.cpp:85
void reset(enum MPL3115A2_BUS busid)
Reset the driver.
Definition: mpl3115a2.cpp:775
struct mpl3115a2::mpl3115a2_bus_option bus_options[]
virtual int close(file_t *filep)
Handle a close of the device.
Definition: CDev.cpp:166
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
float temperature
Definition: sensor_baro.h:57
#define DRV_BARO_DEVTYPE_MPL3115A2
Definition: drv_sensor.h:102
#define ORB_ID(_name)
Generates a pointer to the uORB metadata structure for a given topic.
Definition: uORB.h:87
void perf_count(perf_counter_t handle)
Count a performance event.
float pressure
Definition: sensor_baro.h:56
Abstract class for any character device.
Definition: CDev.hpp:58
void start(unsigned delay_us=1)
Initialize the automatic measurement state machine and start it.
Definition: mpl3115a2.cpp:409
Header common to all counters.
void stop()
Stop the automatic measurement state machine.
Definition: mpl3115a2.cpp:420
void perf_free(perf_counter_t handle)
Free a counter.
MPL3115A2_BUS
Definition: mpl3115a2.cpp:42
void init()
Activates/configures the hardware registers.
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 MPL3115A2_CTRL_REG1
Definition: mpl3115a2.h:81
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
Local functions in support of the shell command.
Definition: mpl3115a2.cpp:579
#define warnx(...)
Definition: err.h:95
bool start_bus(struct mpl3115a2_bus_option &bus)
Start the driver.
Definition: mpl3115a2.cpp:625
void perf_end(perf_counter_t handle)
End a performance event.
void print_info()
Diagnostics - print some basic information about the driver.
Definition: mpl3115a2.cpp:564
virtual int ioctl(struct file *filp, int cmd, unsigned long arg)
Definition: mpl3115a2.cpp:336
__BEGIN_DECLS typedef void * orb_advert_t
ORB topic advertiser handle.
Definition: uORB.h:134
int fd
Definition: dataman.cpp:146
int orb_publish(const struct orb_metadata *meta, orb_advert_t handle, const void *data)
Definition: uORB.cpp:70
virtual int ioctl(unsigned operation, unsigned &arg)
Perform a device-specific operation.
Definition: Device.hpp:124
#define err(eval,...)
Definition: err.h:83
perf_counter_t _sample_perf
Definition: mpl3115a2.cpp:96
void set_device_type(uint8_t devtype)
Definition: Device.hpp:214
#define MPL3115A2_CONVERSION_INTERVAL
Definition: mpl3115a2.cpp:58
virtual bool external() const
Definition: Device.hpp:237
#define CTRL_REG1_OST
Definition: mpl3115a2.h:88
#define IOCTL_MEASURE
Definition: mpl3115a2.h:93
device::Device * MPL3115A2_i2c_interface(uint8_t busnum)
void start(enum MPL3115A2_BUS busid)
Start the driver.
Definition: mpl3115a2.cpp:671
const char * get_devname() const
Get the device name.
Definition: CDev.hpp:169
struct @83::@85::@87 file
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
#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.
void test(enum MPL3115A2_BUS busid)
Perform some basic functional tests on the driver; make sure we can collect data from the sensor in p...
Definition: mpl3115a2.cpp:720
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
#define errx(eval,...)
Definition: err.h:89
float _T
Definition: mpl3115a2.cpp:90
Definition: bst.cpp:62
CDev(const char *devname)
Constructor.
Definition: CDev.cpp:50
virtual int collect()
Collect the result of the most recent measurement.
Definition: mpl3115a2.cpp:502
device::Device * _interface
Definition: mpl3115a2.cpp:81
MPL3115A2(device::Device *interface, const char *path)
Definition: mpl3115a2.cpp:149
#define OK
Definition: uavcan_main.cpp:71
uint64_t timestamp
Definition: sensor_baro.h:53
void Run() override
Perform a poll cycle; collect from the previous measurement and start a new one.
Definition: mpl3115a2.cpp:426
#define OUT_P_MSB
Definition: mpl3115a2.h:79
orb_advert_t orb_advertise_multi(const struct orb_metadata *meta, const void *data, int *instance, int priority)
Definition: uORB.cpp:53
bool _collect_phase
Definition: mpl3115a2.cpp:86
#define MPL3115A2_CTRL_TRIGGER
Definition: mpl3115a2.cpp:60
void perf_begin(perf_counter_t handle)
Begin a performance event.
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
#define NUM_BUS_OPTIONS
Definition: mpl3115a2.cpp:611
virtual int read(unsigned address, void *data, unsigned count)
Read directly from the device.
Definition: Device.hpp:103
virtual int poll(file_t *filep, px4_pollfd_struct_t *fds, bool setup)
Perform a poll setup/teardown operation.
Definition: CDev.cpp:213
#define IOCTL_RESET
Definition: mpl3115a2.h:92
struct mpl3115a2_bus_option & find_bus(enum MPL3115A2_BUS busid)
find a bus structure for a busid
Definition: mpl3115a2.cpp:702
perf_counter_t _measure_perf
Definition: mpl3115a2.cpp:97