PX4 Firmware
PX4 Autopilot Software http://px4.io
mpl3115a2.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2012-2013 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.h
36  *
37  * Shared defines for the mpl3115a2 driver.
38  */
39 
40 #pragma once
41 #include <assert.h>
42 #include <errno.h>
43 #include <fcntl.h>
44 #include <poll.h>
45 #include <semaphore.h>
46 #include <stdbool.h>
47 #include <stdint.h>
48 #include <stdio.h>
49 #include <stdlib.h>
50 #include <string.h>
51 #include <sys/types.h>
52 #include <math.h>
53 #include <unistd.h>
54 
55 #include <arch/board/board.h>
56 #include <board_config.h>
57 #include <drivers/device/device.h>
59 #include <drivers/device/i2c.h>
61 #include <drivers/drv_baro.h>
62 #include <drivers/drv_hrt.h>
63 #include <lib/cdev/CDev.hpp>
64 #include <nuttx/arch.h>
65 #include <nuttx/clock.h>
66 #include <perf/perf_counter.h>
67 #include <px4_platform_common/px4_config.h>
68 #include <px4_platform_common/defines.h>
69 #include <px4_platform_common/getopt.h>
70 #include <px4_platform_common/log.h>
71 #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
72 #include <systemlib/err.h>
73 
74 #include "board_config.h"
75 
76 #define MPL3115A2_REG_WHO_AM_I 0x0c
77 #define MPL3115A2_WHO_AM_I 0xC4
78 
79 #define OUT_P_MSB 0x01
80 
81 #define MPL3115A2_CTRL_REG1 0x26
82 # define CTRL_REG1_ALT (1 << 7)
83 # define CTRL_REG1_RAW (1 << 6)
84 # define CTRL_REG1_OS_SHIFTS (3)
85 # define CTRL_REG1_OS_MASK (0x7 << CTRL_REG1_OS_SHIFTS)
86 # define CTRL_REG1_OS(n) (((n)& 0x7) << CTRL_REG1_OS_SHIFTS)
87 # define CTRL_REG1_RST (1 << 2)
88 # define CTRL_REG1_OST (1 << 1)
89 # define CTRL_REG1_SBYB (1 << 0)
90 
91 /* interface ioctls */
92 #define IOCTL_RESET 1
93 #define IOCTL_MEASURE 2
94 
95 typedef begin_packed_struct struct MPL3115A2_data_t {
96  union {
97  uint32_t q;
98  uint16_t w[sizeof(q) / sizeof(uint16_t)];
99  uint8_t b[sizeof(q) / sizeof(uint8_t)];
100  } pressure;
101 
102  union {
103  uint16_t w;
104  uint8_t b[sizeof(w)];
105  } temperature;
106 } end_packed_struct MPL3115A2_data_t;
107 
108 /* interface factories */
109 extern device::Device *MPL3115A2_i2c_interface(uint8_t busnum);
110 extern device::Device *MPL3115A2_sim_interface(uint8_t busnum);
111 typedef device::Device *(*MPL3115A2_constructor)(uint8_t busnum);
High-resolution timer with callouts and timekeeping.
device::Device * MPL3115A2_sim_interface(uint8_t busnum)
Definitions for the generic base classes in the device framework.
union MPL3115A2_data_t::@1 temperature
union MPL3115A2_data_t::@0 pressure
uint8_t b[sizeof(q)/sizeof(uint8_t)]
Definition: mpl3115a2.h:99
Simple error/warning functions, heavily inspired by the BSD functions of the same names...
uint32_t q
Definition: mpl3115a2.h:97
device::Device * MPL3115A2_i2c_interface(uint8_t busnum)
begin_packed_struct struct MPL3115A2_data_t MPL3115A2_data_t
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
uint16_t w[sizeof(q)/sizeof(uint16_t)]
Definition: mpl3115a2.h:98
Barometric pressure sensor driver interface.
Performance measuring tools.
Base class for devices connected via I2C.