APM:Libraries
AP_Baro_FBM320.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  FCM320 barometer driver
17  */
18 
19 #include "AP_Baro_FBM320.h"
20 
21 #include <utility>
22 #include <stdio.h>
23 
24 extern const AP_HAL::HAL &hal;
25 
26 #define FBM320_REG_ID 0x6B
27 #define FBM320_REG_DATA 0xF6
28 #define FBM320_REG_CMD 0xF4
29 
30 #define FBM320_CMD_READ_T 0x2E
31 #define FBM320_CMD_READ_P 0xF4
32 
33 #define FBM320_WHOAMI 0x42
34 
36  : AP_Baro_Backend(baro)
37  , dev(std::move(_dev))
38 {
39 }
40 
43 {
44  if (!_dev) {
45  return nullptr;
46  }
47 
48  AP_Baro_FBM320 *sensor = new AP_Baro_FBM320(baro, std::move(_dev));
49  if (!sensor || !sensor->init()) {
50  delete sensor;
51  return nullptr;
52  }
53  return sensor;
54 }
55 
56 /*
57  read calibration data
58  */
60 {
61  uint8_t tmp[2];
62  uint16_t R[10];
63 
64  for (uint8_t i=0; i<9; i++) {
65  if (!dev->read_registers(0xAA+(i*2),&tmp[0],1)) {
66  return false;
67  }
68  if (!dev->read_registers(0xAB+(i*2),&tmp[1],1)) {
69  return false;
70  }
71  R[i] = ((uint8_t)tmp[0] << 8 | tmp[1]);
72  }
73 
74  if (!dev->read_registers(0xA4,&tmp[0],1)) {
75  return false;
76  }
77  if (!dev->read_registers(0xF1,&tmp[0],1)) {
78  return false;
79  }
80  R[9] = ((uint8_t)tmp[0] << 8) | tmp[1];
81 
82 
83  /* Use R0~R9 calculate C0~C12 of FBM320-02 */
84  calibration.C0 = R[0] >> 4;
85  calibration.C1 = ((R[1] & 0xFF00) >> 5) | (R[2] & 7);
86  calibration.C2 = ((R[1] & 0xFF) << 1) | (R[4] & 1);
87  calibration.C3 = R[2] >> 3;
88  calibration.C4 = ((uint32_t)R[3] << 2) | (R[0] & 3);
89  calibration.C5 = R[4] >> 1;
90  calibration.C6 = R[5] >> 3;
91  calibration.C7 = ((uint32_t)R[6] << 3) | (R[5] & 7);
92  calibration.C8 = R[7] >> 3;
93  calibration.C9 = R[8] >> 2;
94  calibration.C10 = ((R[9] & 0xFF00) >> 6) | (R[8] & 3);
95  calibration.C11 = R[9] & 0xFF;
96  calibration.C12 = ((R[0] & 0x0C) << 1) | (R[7] & 7);
97 
98  return true;
99 }
100 
102 {
104  return false;
105  }
106 
108 
109  uint8_t whoami;
110  if (!dev->read_registers(FBM320_REG_ID, &whoami, 1) ||
111  whoami != FBM320_WHOAMI) {
112  // not a FBM320
113  dev->get_semaphore()->give();
114  return false;
115  }
116  printf("FBM320 ID 0x%x\n", whoami);
117 
118  if (!read_calibration()) {
119  dev->get_semaphore()->give();
120  return false;
121  }
122 
124 
126 
127  dev->get_semaphore()->give();
128 
129  // request 50Hz update
131 
132  return true;
133 }
134 
135 /*
136  calculate corrected pressure and temperature
137  */
138 void AP_Baro_FBM320::calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int32_t &temperature)
139 {
140  const struct fbm320_calibration &cal = calibration;
141  int32_t DT, DT2, X01, X02, X03, X11, X12, X13, X21, X22, X23, X24, X25, X26, X31, X32, CF, PP1, PP2, PP3, PP4;
142 
143  DT = ((UT - 8388608) >> 4) + (cal.C0 << 4);
144  X01 = (cal.C1 + 4459) * DT >> 1;
145  X02 = ((((cal.C2 - 256) * DT) >> 14) * DT) >> 4;
146  X03 = (((((cal.C3 * DT) >> 18) * DT) >> 18) * DT);
147 
148  temperature = ((2500 << 15) - X01 - X02 - X03) >> 15;
149 
150  DT2 = (X01 + X02 + X03) >> 12;
151  X11 = ((cal.C5 - 4443) * DT2);
152  X12 = (((cal.C6 * DT2) >> 16) * DT2) >> 2;
153  X13 = ((X11 + X12) >> 10) + ((cal.C4 + 120586) << 4);
154 
155  X21 = ((cal.C8 + 7180) * DT2) >> 10;
156  X22 = (((cal.C9 * DT2) >> 17) * DT2) >> 12;
157  X23 = (X22 >= X21) ? (X22 - X21) : (X21 - X22);
158 
159  X24 = (X23 >> 11) * (cal.C7 + 166426);
160  X25 = ((X23 & 0x7FF) * (cal.C7 + 166426)) >> 11;
161  X26 = (X21 >= X22) ? (((0 - X24 - X25) >> 11) + cal.C7 + 166426) : (((X24 + X25) >> 11) + cal.C7 + 166426);
162 
163  PP1 = ((UP - 8388608) - X13) >> 3;
164  PP2 = (X26 >> 11) * PP1;
165  PP3 = ((X26 & 0x7FF) * PP1) >> 11;
166  PP4 = (PP2 + PP3) >> 10;
167 
168  CF = (2097152 + cal.C12 * DT2) >> 3;
169  X31 = (((CF * cal.C10) >> 17) * PP4) >> 2;
170  X32 = (((((CF * cal.C11) >> 15) * PP4) >> 18) * PP4);
171 
172  pressure = ((X31 + X32) >> 15) + PP4 + 99880;
173 }
174 
175 // acumulate a new sensor reading
177 {
178  uint8_t buf[3];
179 
180  if (!dev->read_registers(0xF6, buf, sizeof(buf))) {
181  return;
182  }
183  int32_t value = ((uint32_t)buf[0] << 16) | ((uint32_t)buf[1] << 8) | (uint32_t)buf[2];
184 
185  if (step == 0) {
186  value_T = value;
187  } else {
188  int32_t pressure, temperature;
189  calculate_PT(value_T, value, pressure, temperature);
190  if (pressure_ok(pressure) && _sem->take_nonblocking()) {
191  pressure_sum += pressure;
192  // sum and convert to degrees
193  temperature_sum += temperature*0.01;
194  count++;
195  _sem->give();
196  }
197  }
198 
199  if (step++ >= 5) {
201  step = 0;
202  } else {
204  }
205 }
206 
207 // transfer data to the frontend
209 {
210  if (count != 0 && _sem->take_nonblocking()) {
211  if (count == 0) {
212  _sem->give();
213  return;
214  }
215 
217  pressure_sum = 0;
218  temperature_sum = 0;
219  count=0;
220 
221  _sem->give();
222  }
223 }
struct AP_Baro_FBM320::fbm320_calibration calibration
int printf(const char *fmt,...)
Definition: stdio.c:113
#define AP_USEC_PER_MSEC
Definition: definitions.h:93
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
void _copy_to_frontend(uint8_t instance, float pressure, float temperature)
uint8_t register_sensor(void)
Definition: AP_Baro.cpp:705
AP_HAL::Semaphore * _sem
virtual AP_HAL::Semaphore * get_semaphore()=0
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
#define FBM320_CMD_READ_P
bool read_calibration(void)
float temperature
Definition: Airspeed.cpp:32
virtual bool take_nonblocking() WARN_IF_UNUSED=0
AP_Baro & _frontend
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
AP_HAL::OwnPtr< AP_HAL::Device > dev
virtual bool set_speed(Speed speed)=0
AP_Baro_FBM320(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
static AP_Baro baro
Definition: ModuleTest.cpp:18
bool pressure_ok(float press)
#define FBM320_WHOAMI
#define FBM320_REG_CMD
virtual bool give()=0
#define FBM320_CMD_READ_T
float value
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define FBM320_REG_ID
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
void calculate_PT(int32_t UT, int32_t UP, int32_t &pressure, int32_t &temperature)