APM:Libraries
AP_Baro_KellerLD.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 #include "AP_Baro_KellerLD.h"
17 
18 #include <utility>
19 #include <stdio.h>
20 
21 #include <AP_Math/AP_Math.h>
22 
23 #define KELLER_DEBUG 0
24 
25 #if KELLER_DEBUG
26 # define Debug(fmt, args ...) do {printf(fmt "\n", ## args);} while(0)
27 #else
28 # define Debug(fmt, args ...)
29 #endif
30 
31 extern const AP_HAL::HAL &hal;
32 
33 // Measurement range registers
34 static const uint8_t CMD_PRANGE_MIN_MSB = 0x13;
35 static const uint8_t CMD_PRANGE_MIN_LSB = 0x14;
36 static const uint8_t CMD_PRANGE_MAX_MSB = 0x15;
37 static const uint8_t CMD_PRANGE_MAX_LSB = 0x16;
38 
39 // write to this address to start pressure measurement
40 static const uint8_t CMD_REQUEST_MEASUREMENT = 0xAC;
41 
43  : AP_Baro_Backend(baro)
44  , _dev(std::move(dev))
45 {
46 }
47 
48 // Look for the device on the bus and see if it responds appropriately
50 {
51  if (!dev) {
52  return nullptr;
53  }
54  AP_Baro_KellerLD *sensor = new AP_Baro_KellerLD(baro, std::move(dev));
55  if (!sensor || !sensor->_init()) {
56  delete sensor;
57  return nullptr;
58  }
59  return sensor;
60 }
61 
62 // The hardware does not need to be reset/initialized
63 // We read out the measurement range to be used in raw value conversions
65 {
66  if (!_dev) {
67  return false;
68  }
69 
71  AP_HAL::panic("PANIC: AP_Baro_KellerLD: failed to take serial semaphore for init");
72  }
73 
74  // high retries for init
75  _dev->set_retries(10);
76 
77  bool cal_read_ok = true;
78 
79  uint8_t data[3];
80  uint16_t ms_word, ls_word;
81 
82  // This device has some undocumented finicky quirks and requires delays when reading out the
83  // measurement range, but for some reason this isn't an issue when requesting measurements.
84  // This is why we need to split the transfers with delays like this.
85  // (Using AP_HAL::I2CDevice::set_split_transfers will not work with these sensors)
86 
87  // Read out pressure measurement range
88  cal_read_ok &= _dev->transfer(&CMD_PRANGE_MIN_MSB, 1, nullptr, 0);
89  hal.scheduler->delay(1);
90  cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
91  hal.scheduler->delay(1);
92 
93  ms_word = (data[1] << 8) | data[2];
94  Debug("0x13: %d [%d, %d, %d]", ms_word, data[0], data[1], data[2]);
95 
96  cal_read_ok &= _dev->transfer(&CMD_PRANGE_MIN_LSB, 1, nullptr, 0);
97  hal.scheduler->delay(1);
98  cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
99  hal.scheduler->delay(1);
100 
101  ls_word = (data[1] << 8) | data[2];
102  Debug("0x14: %d [%d, %d, %d]", ls_word, data[0], data[1], data[2]);
103 
104  uint32_t cal_data = (ms_word << 16) | ls_word;
105  memcpy(&_p_min, &cal_data, sizeof(_p_min));
106  Debug("data: %d, p_min: %.2f", cal_data, _p_min);
107 
108  cal_read_ok &= _dev->transfer(&CMD_PRANGE_MAX_MSB, 1, nullptr, 0);
109  hal.scheduler->delay(1);
110  cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
111  hal.scheduler->delay(1);
112 
113  ms_word = (data[1] << 8) | data[2];
114  Debug("0x15: %d [%d, %d, %d]", ms_word, data[0], data[1], data[2]);
115 
116  cal_read_ok &= _dev->transfer(&CMD_PRANGE_MAX_LSB, 1, nullptr, 0);
117  hal.scheduler->delay(1);
118  cal_read_ok &= _dev->transfer(nullptr, 0, &data[0], 3);
119  hal.scheduler->delay(1);
120 
121  ls_word = (data[1] << 8) | data[2];
122  Debug("0x16: %d [%d, %d, %d]", ls_word, data[0], data[1], data[2]);
123 
124  cal_data = (ms_word << 16) | ls_word;
125  memcpy(&_p_max, &cal_data, sizeof(_p_max));
126  Debug("data: %d, p_max: %.2f", cal_data, _p_max);
127 
128  cal_read_ok &= !isnan(_p_min) && !isinf(_p_min) && !isnan(_p_max) && !isinf(_p_max);
129 
130  cal_read_ok &= _p_max > _p_min;
131 
132  if (!cal_read_ok) {
133  printf("Cal read bad!\n");
134  _dev->get_semaphore()->give();
135  return false;
136  }
137 
138  printf("Keller LD found on bus %u address 0x%02x\n", _dev->bus_num(), _dev->get_bus_address());
139 
140  // Send a command to take a measurement
141  _dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);
142 
143  memset(&_accum, 0, sizeof(_accum));
144 
146 
148 
149  // lower retries for run
150  _dev->set_retries(3);
151 
152  _dev->get_semaphore()->give();
153 
154  // The sensor needs time to take a deep breath after reading out the calibration...
155  hal.scheduler->delay(150);
156 
157  // Request 50Hz update
158  // The sensor really struggles with any jitter in timing at 100Hz, and will sometimes start reading out all zeros
161  return true;
162 }
163 
164 // Read out most recent measurement from sensor hw
166 {
167  uint8_t data[5];
168  if (!_dev->transfer(0x0, 1, data, sizeof(data))) {
169  Debug("Keller LD read failed!");
170  return false;
171  }
172 
173  //uint8_t status = data[0];
174  uint16_t pressure_raw = (data[1] << 8) | data[2];
175  uint16_t temperature_raw = (data[3] << 8) | data[4];
176 
177 #if KELLER_DEBUG
178  static uint8_t samples = 0;
179  if (samples < 3) {
180  samples++;
181  Debug("data: [%d, %d, %d, %d, %d]", data[0], data[1], data[2], data[3], data[4]);
182  Debug("pressure_raw: %d\ttemperature_raw: %d", pressure_raw, temperature_raw);
183  }
184 #endif
185 
186  if (pressure_raw == 0 || temperature_raw == 0) {
187  Debug("Keller: bad read");
188  return false;
189  }
190 
191  if (!pressure_ok(pressure_raw)) {
192  return false;
193  }
195  _update_and_wrap_accumulator(pressure_raw, temperature_raw, 128);
196  _sem->give();
197  return true;
198  }
199  return false;
200 }
201 
202 // Periodic callback, regular update at 50Hz
203 // Read out most recent measurement, and request another
204 // Max conversion time according to datasheet is ~8ms, so
205 // max update rate is ~125Hz, yet we struggle to get consistent
206 // performance/data at 100Hz
208 {
209  _read();
210  _dev->transfer(&CMD_REQUEST_MEASUREMENT, 1, nullptr, 0);
211 }
212 
213 // Accumulate a reading, shrink if necessary to prevent overflow
214 void AP_Baro_KellerLD::_update_and_wrap_accumulator(uint16_t pressure, uint16_t temperature, uint8_t max_count)
215 {
216  _accum.sum_pressure += pressure;
217  _accum.sum_temperature += temperature;
218  _accum.num_samples += 1;
219 
220  if (_accum.num_samples == max_count) {
221  _accum.sum_pressure /= 2;
222  _accum.sum_temperature /= 2;
223  _accum.num_samples /= 2;
224  }
225 }
226 
227 // Take the average of accumulated values and push to frontend
229 {
231  float num_samples;
232 
234  return;
235  }
236 
237  if (_accum.num_samples == 0) {
238  _sem->give();
239  return;
240  }
241 
242  sum_pressure = _accum.sum_pressure;
243  sum_temperature = _accum.sum_temperature;
244  num_samples = _accum.num_samples;
245  memset(&_accum, 0, sizeof(_accum));
246 
247  _sem->give();
248 
249  uint16_t raw_pressure_avg = sum_pressure / num_samples;
250  uint16_t raw_temperature_avg = sum_temperature / num_samples;
251 
252  // per datasheet
253  float pressure = (raw_pressure_avg - 16384) * (_p_max - _p_min) / 32768 + _p_min;
254  pressure *= 100000; // bar -> Pascal
255  pressure += 101300; // MSL pressure offset
256  float temperature = ((raw_temperature_avg >> 4) - 24) * 0.05f - 50;
257 
258  _copy_to_frontend(_instance, pressure, temperature);
259 }
int printf(const char *fmt,...)
Definition: stdio.c:113
#define AP_USEC_PER_MSEC
Definition: definitions.h:93
virtual PeriodicHandle register_periodic_callback(uint32_t period_usec, PeriodicCb)=0
AP_Baro_KellerLD(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
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
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual AP_HAL::Semaphore * get_semaphore()=0
virtual void set_retries(uint8_t retries)
Definition: Device.h:260
AP_HAL::OwnPtr< AP_HAL::Device > _dev
uint8_t get_bus_address(void) const
Definition: Device.h:65
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
struct AP_Baro_KellerLD::@9 _accum
static const uint8_t CMD_PRANGE_MAX_MSB
uint8_t bus_num(void) const
Definition: Device.h:55
float temperature
Definition: Airspeed.cpp:32
virtual void delay(uint16_t ms)=0
AP_Baro & _frontend
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define Debug(fmt, args ...)
uint32_t sum_temperature
void _update_and_wrap_accumulator(uint16_t pressure, uint16_t temperature, uint8_t max_count)
static const uint8_t CMD_PRANGE_MIN_LSB
static AP_Baro baro
Definition: ModuleTest.cpp:18
static const uint8_t CMD_PRANGE_MIN_MSB
bool pressure_ok(float press)
static const uint8_t CMD_PRANGE_MAX_LSB
virtual bool give()=0
static const uint8_t CMD_REQUEST_MEASUREMENT
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)=0
void set_type(uint8_t instance, baro_type_t type)
Definition: AP_Baro.h:136
static AP_Baro_Backend * probe(AP_Baro &baro, AP_HAL::OwnPtr< AP_HAL::Device > dev)
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114