PX4 Firmware
PX4 Autopilot Software http://px4.io
BMI088_accel.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 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 #include "BMI088_accel.hpp"
35 
36 /*
37  * Global variable of the accelerometer temperature reading, to read it in the bmi055_gyro driver. The variable is changed in bmi055_accel.cpp.
38  * This is a HACK! The driver should be rewritten with the gyro as subdriver.
39  */
40 extern float _accel_last_temperature_copy;
41 
42 /*
43  list of registers that will be checked in check_registers(). Note
44  that ADDR_WHO_AM_I must be first in the list.
45  */
53  };
54 
55 BMI088_accel::BMI088_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation) :
56  BMI088("BMI088_ACCEL", path_accel, bus, device, SPIDEV_MODE3, BMI088_BUS_SPEED, rotation),
57  ScheduledWorkItem(MODULE_NAME, px4::device_bus_to_wq(get_device_id())),
58  _px4_accel(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
59  _sample_perf(perf_alloc(PC_ELAPSED, "bmi088_accel_read")),
60  _bad_transfers(perf_alloc(PC_COUNT, "bmi088_accel_bad_transfers")),
61  _bad_registers(perf_alloc(PC_COUNT, "bmi088_accel_bad_registers")),
62  _duplicates(perf_alloc(PC_COUNT, "bmi088_accel_duplicates")),
63  _got_duplicate(false)
64 {
66 }
67 
69 {
70  /* make sure we are truly inactive */
71  stop();
72 
73  /* delete the perf counter */
78 }
79 
80 int
82 {
83  /* do SPI init (and probe) first */
84  int ret = SPI::init();
85 
86  /* if probe/setup failed, bail now */
87  if (ret != OK) {
88  DEVICE_DEBUG("SPI setup failed");
89  return ret;
90  }
91 
92  return reset();
93 }
94 
95 uint8_t
97 {
98  // For the BMI088, you need to read out a dummy byte before you can read out the normal data (see section "SPI interface of accelerometer part" of the BMI088 datasheet)
99  uint8_t cmd[3] = { (uint8_t)(reg | DIR_READ), 0, 0};
100 
101  transfer(cmd, cmd, sizeof(cmd));
102 
103  return cmd[2]; // Skip dummy byte in cmd[1] and read out actual data
104 }
105 
106 uint16_t
108 {
109  // For the BMI088, you need to read out the dummy byte before you can read out the normal data (see section "SPI interface of accelerometer part" of the BMI088 datasheet)
110  uint8_t cmd[4] = { (uint8_t)(reg | DIR_READ), 0, 0, 0 };
111 
112  transfer(cmd, cmd, sizeof(cmd));
113 
114  return (uint16_t)(cmd[2] << 8) | cmd[3]; // Skip dummy byte in cmd[1]
115 }
116 
118 {
120  /* After a POR or soft-reset, the sensor needs up to 1ms boot time
121  * (see section "Power Modes: Accelerometer" in the BMI088 datasheet).
122  * Based off of testing it seems this value needs to be increased from 1ms.
123  * Setting it to 5ms.
124  */
125 
126  up_udelay(5000);
127 
128  // Perform a dummy read here to put the accelerometer part of the BMI088 back into SPI mode after the reset
129  // The dummy read basically pulls the chip select line low and then high
130  // See section "Serial Peripheral Interface (SPI)" of the BMI088 datasheet for more details.
132 
133  // Enable Accelerometer
134  // The accelerometer needs to be enabled first, before writing to its registers
136  /* After changing power modes, the sensor requires up to 5ms to settle.
137  * Any communication with the sensor during this time should be avoided
138  * (see section "Power Modes: Acceleromter" in the BMI datasheet) */
139 
140  up_udelay(5000);
141 
142  // Set the PWR CONF to be active
143  write_checked_reg(BMI088_ACC_PWR_CONF, BMI088_ACC_PWR_CONF_ACTIVE); // Sets the accelerometer to active mode
144 
145  // Write accel bandwidth and output data rate
146  // ToDo set the bandwidth
149 
150  // Configure the accel INT1
153  BMI088_ACC_INT1_IO_CONF_ACTIVE_HIGH); // Configure INT1 pin as output, push-pull, active high
155  BMI088_ACC_INT1_INT2_MAP_DATA_INT1_DRDY); // Map DRDY interrupt on pin INT1
156 
157  uint8_t retries = 10;
158 
159  while (retries--) {
160  bool all_ok = true;
161 
162  for (uint8_t i = 0; i < BMI088_ACCEL_NUM_CHECKED_REGISTERS; i++) {
165  all_ok = false;
166  }
167  }
168 
169  if (all_ok) {
170  break;
171  }
172  }
173 
174  return OK;
175 }
176 
177 int
179 {
180  // Perform a dummy read here to put the accelerometer part of the BMI088 back into SPI mode after the reset
181  // The dummy read basically pulls the chip select line low and then high
182  // See section "Serial Peripheral Interface (SPI)" of the BMI088 datasheet for more details.
184 
185  /* look for device ID */
187 
188  // verify product revision
189  switch (_whoami) {
190  case BMI088_ACC_WHO_AM_I:
191  memset(_checked_values, 0, sizeof(_checked_values));
192  memset(_checked_bad, 0, sizeof(_checked_bad));
194  _checked_bad[0] = _whoami;
195  return OK;
196  }
197 
198  DEVICE_DEBUG("unexpected whoami 0x%02x", _whoami);
199  return -EIO;
200 }
201 
202 int
204 {
205  uint8_t setbits = 0;
206  uint8_t clearbits = 0x0F;
207 
208  if (frequency < 25) {
209  setbits |= BMI088_ACC_CONF_ODR_12_5;
210  //_accel_sample_rate = 12.5f;
211 
212  } else if (frequency < 50) {
213  setbits |= BMI088_ACC_CONF_ODR_25;
214  //_accel_sample_rate = 25.f;
215 
216  } else if (frequency < 100) {
217  setbits |= BMI088_ACC_CONF_ODR_50;
218  //_accel_sample_rate = 50.f;
219 
220  } else if (frequency < 200) {
221  setbits |= BMI088_ACC_CONF_ODR_100;
222  //_accel_sample_rate = 100.f;
223 
224  } else if (frequency < 400) {
225  setbits |= BMI088_ACC_CONF_ODR_200;
226  //_accel_sample_rate = 200.f;
227 
228  } else if (frequency < 800) {
229  setbits |= BMI088_ACC_CONF_ODR_400;
230  //_accel_sample_rate = 400.f;
231 
232  } else if (frequency < 1600) {
233  setbits |= BMI088_ACC_CONF_ODR_800;
234  //_accel_sample_rate = 800.f;
235 
236  } else if (frequency >= 1600) {
237  setbits |= BMI088_ACC_CONF_ODR_1600;
238  //_accel_sample_rate = 1600.f;
239 
240  } else {
241  printf("Set sample rate error \n");
242  return -EINVAL;
243  }
244 
245  /* Write accel ODR */
246  modify_reg(BMI088_ACC_CONF, clearbits, setbits);
247 
248  return OK;
249 }
250 
251 /*
252  deliberately trigger an error in the sensor to trigger recovery
253  */
254 void
256 {
258  ::printf("error triggered\n");
259  print_registers();
260 }
261 
262 void
263 BMI088_accel::modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
264 {
265  uint8_t val = read_reg(reg);
266  val &= ~clearbits;
267  val |= setbits;
268  write_checked_reg(reg, val);
269 }
270 
271 void
272 BMI088_accel::write_checked_reg(unsigned reg, uint8_t value)
273 {
274  write_reg(reg, value);
275 
276  for (uint8_t i = 0; i < BMI088_ACCEL_NUM_CHECKED_REGISTERS; i++) {
277  if (reg == _checked_registers[i]) {
278  _checked_values[i] = value;
279  _checked_bad[i] = value;
280  }
281  }
282 }
283 
284 int
286 {
287  uint8_t setbits = 0;
288  uint8_t clearbits = BMI088_ACCEL_RANGE_24_G;
289  float lsb_per_g;
290 
291  if (max_g == 0) {
292  max_g = 24;
293  }
294 
295  if (max_g <= 3) {
296  //max_accel_g = 3;
297  setbits |= BMI088_ACCEL_RANGE_3_G;
298  lsb_per_g = 10922.67;
299 
300  } else if (max_g <= 6) {
301  //max_accel_g = 6;
302  setbits |= BMI088_ACCEL_RANGE_6_G;
303  lsb_per_g = 5461.33;
304 
305  } else if (max_g <= 12) {
306  //max_accel_g = 12;
307  setbits |= BMI088_ACCEL_RANGE_12_G;
308  lsb_per_g = 2730.67;
309 
310  } else if (max_g <= 24) {
311  //max_accel_g = 24;
312  setbits |= BMI088_ACCEL_RANGE_24_G;
313  lsb_per_g = 1365.33;
314 
315  } else {
316  return -EINVAL;
317  }
318 
319  _px4_accel.set_scale(CONSTANTS_ONE_G / lsb_per_g);
320 
321  modify_reg(BMI088_ACC_RANGE, clearbits, setbits);
322 
323  return OK;
324 }
325 
326 void
328 {
329  /* make sure we are stopped first */
330  stop();
331 
332  // Reset the accelerometer
333  reset();
334 
335  /* start polling at the specified rate */
336  ScheduleOnInterval(BMI088_ACCEL_DEFAULT_RATE - BMI088_TIMER_REDUCTION, 1000);
337 
338 }
339 
340 void
342 {
343  ScheduleClear();
344 }
345 
346 void
348 {
349  /* make another measurement */
350  measure();
351 }
352 
353 void
355 {
356  uint8_t v;
357 
359  _checked_values[_checked_next]) {
361 
362  /*
363  if we get the wrong value then we know the SPI bus
364  or sensor is very sick. We set _register_wait to 20
365  and wait until we have seen 20 good values in a row
366  before we consider the sensor to be OK again.
367  */
369 
370  /*
371  try to fix the bad register value. We only try to
372  fix one per loop to prevent a bad sensor hogging the
373  bus.
374  */
375  if (_register_wait == 0 || _checked_next == 0) {
376  // if the product_id is wrong then reset the
377  // sensor completely
379  _reset_wait = hrt_absolute_time() + 10000;
380  _checked_next = 0;
381 
382  } else {
383  write_reg(_checked_registers[_checked_next], _checked_values[_checked_next]);
384  // waiting 3ms between register writes seems
385  // to raise the chance of the sensor
386  // recovering considerably
387  _reset_wait = hrt_absolute_time() + 3000;
388  }
389 
390  _register_wait = 20;
391  }
392 
393  _checked_next = (_checked_next + 1) % BMI088_ACCEL_NUM_CHECKED_REGISTERS;
394 }
395 
396 void
398 {
399  if (hrt_absolute_time() < _reset_wait) {
400  // we're waiting for a reset to complete
401  return;
402  }
403 
404  struct Report {
405  int16_t accel_x;
406  int16_t accel_y;
407  int16_t accel_z;
408  int16_t temp;
409  } report;
410 
411  /* start measuring */
413 
414  // Checking the status of new data
415  uint8_t status;
416  status = read_reg(BMI088_ACC_STATUS);
417 
418  if (!(status & BMI088_ACC_STATUS_DRDY)) {
421  _got_duplicate = true;
422  return;
423  }
424 
425  _got_duplicate = false;
426 
427  /*
428  * Fetch the full set of measurements from the BMI088 in one pass.
429  */
430  uint8_t index = 0;
431  uint8_t accel_data[8]; // Need an extra byte for the command, and an an extra dummy byte for the read (see section "SPI interface of accelerometer part" of the BMI088 datasheet)
432  accel_data[index] = BMI088_ACC_X_L | DIR_READ;
433 
434  const hrt_abstime timestamp_sample = hrt_absolute_time();
435 
436  if (OK != transfer(accel_data, accel_data, sizeof(accel_data))) {
437  return;
438  }
439 
440  check_registers();
441 
442  /* Extracting accel data from the read data */
443  index = 2; // Skip the dummy byte at index=1
444  uint16_t lsb, msb, msblsb;
445 
446  lsb = (uint16_t)accel_data[index++];
447  msb = (uint16_t)accel_data[index++];
448  msblsb = (msb << 8) | lsb;
449  report.accel_x = (int16_t)msblsb; /* Data in X axis */
450 
451  lsb = (uint16_t)accel_data[index++];
452  msb = (uint16_t)accel_data[index++];
453  msblsb = (msb << 8) | lsb;
454  report.accel_y = (int16_t)msblsb; /* Data in Y axis */
455 
456  lsb = (uint16_t)accel_data[index++];
457  msb = (uint16_t)accel_data[index++];
458  msblsb = (msb << 8) | lsb;
459  report.accel_z = (int16_t)msblsb; /* Data in Z axis */
460 
461  // Extract the temperature data
462  // Note: the temp sensor data is only updated every 1.28s (see "Register 0x22-0x23 Temperature Sensor Data" section in BMI088 Datasheet)
463  index = 0;
464  accel_data[index] = BMI088_ACC_TEMP_H | DIR_READ;
465 
466  // Need to perform a dummy read, hence the num bytes to read is 3 (plus 1 send byte)
467  if (OK != transfer(accel_data, accel_data, 4)) {
468  return;
469  }
470 
471  index = 2;
472  msb = (uint16_t)accel_data[index++];
473  lsb = (uint16_t)accel_data[index++];
474  uint16_t temp = msb * 8 + lsb / 32;
475 
476  if (temp > 1023) {
477  report.temp = temp - 2048;
478 
479  } else {
480  report.temp = temp;
481  }
482 
483 
484  if (report.accel_x == 0 &&
485  report.accel_y == 0 &&
486  report.accel_z == 0) {
487  // all zero data - probably a SPI bus error
490  // note that we don't call reset() here as a reset()
491  // costs 20ms with interrupts disabled. That means if
492  // the bmi088 accel does go bad it would cause a FMU failure,
493  // regardless of whether another sensor is available,
494  return;
495  }
496 
497  if (_register_wait != 0) {
498  // we are waiting for some good transfers before using
499  // the sensor again, but don't return any data yet
500  _register_wait--;
501  return;
502  }
503 
504  // report the error count as the sum of the number of bad
505  // transfers and bad register reads. This allows the higher
506  // level code to decide if it should use this sensor based on
507  // whether it has had failures
508  const uint64_t error_count = perf_event_count(_bad_transfers) + perf_event_count(_bad_registers);
509  _px4_accel.set_error_count(error_count);
510 
511  // Convert the bit-wise representation of temperature to degrees C
512  _accel_last_temperature_copy = (report.temp * 0.125f) + 23.0f;
514 
515  /*
516  * 1) Scale raw value to SI units using scaling from datasheet.
517  * 2) Subtract static offset (in SI units)
518  * 3) Scale the statically calibrated values with a linear
519  * dynamically obtained factor
520  *
521  * Note: the static sensor offset is the number the sensor outputs
522  * at a nominally 'zero' input. Therefore the offset has to
523  * be subtracted.
524  *
525  */
526  _px4_accel.update(timestamp_sample, report.accel_x, report.accel_y, report.accel_z);
527 
528  /* stop measuring */
530 }
531 
532 void
534 {
535  PX4_INFO("Accel");
536 
541 
542  ::printf("checked_next: %u\n", _checked_next);
543 
544  for (uint8_t i = 0; i < BMI088_ACCEL_NUM_CHECKED_REGISTERS; i++) {
545  uint8_t v = read_reg(_checked_registers[i]);
546 
547  if (v != _checked_values[i]) {
548  ::printf("reg %02x:%02x should be %02x\n",
549  (unsigned)_checked_registers[i],
550  (unsigned)v,
551  (unsigned)_checked_values[i]);
552  }
553 
554  if (v != _checked_bad[i]) {
555  ::printf("reg %02x:%02x was bad %02x\n",
556  (unsigned)_checked_registers[i],
557  (unsigned)v,
558  (unsigned)_checked_bad[i]);
559  }
560  }
561 
563 }
564 
565 void
567 {
568  uint8_t index = 0;
569  printf("BMI088 accel registers\n");
570 
571  uint8_t reg = _checked_registers[index++];
572  uint8_t v = read_reg(reg);
573  printf("Accel Chip Id: %02x:%02x ", (unsigned)reg, (unsigned)v);
574  printf("\n");
575 
576  reg = _checked_registers[index++];
577  v = read_reg(reg);
578  printf("Accel Conf: %02x:%02x ", (unsigned)reg, (unsigned)v);
579  printf("\n");
580 
581  reg = _checked_registers[index++];
582  v = read_reg(reg);
583  printf("Accel Range: %02x:%02x ", (unsigned)reg, (unsigned)v);
584  printf("\n");
585 
586  reg = _checked_registers[index++];
587  v = read_reg(reg);
588  printf("Accel Int1 Conf: %02x:%02x ", (unsigned)reg, (unsigned)v);
589  printf("\n");
590 
591  reg = _checked_registers[index++];
592  v = read_reg(reg);
593  printf("Accel Int1-Int2_Map-Data: %02x:%02x ", (unsigned)reg, (unsigned)v);
594  printf("\n");
595 
596  reg = _checked_registers[index++];
597  v = read_reg(reg);
598  printf("Accel Pwr Conf: %02x:%02x ", (unsigned)reg, (unsigned)v);
599  printf("\n");
600 
601  reg = _checked_registers[index++];
602  v = read_reg(reg);
603  printf("Accel Pwr Ctrl: %02x:%02x ", (unsigned)reg, (unsigned)v);
604  printf("\n");
605 
606 
607 
608  printf("\n");
609 }
void measure()
Fetch measurements from the sensor and update the report buffers.
virtual uint8_t read_reg(unsigned reg)
Read a register from the BMI088.
#define BMI088_ACCEL_RANGE_24_G
void print_info()
Diagnostics - print some basic information about the driver.
static struct vehicle_status_s status
Definition: Commander.cpp:138
measure the time elapsed performing an event
Definition: perf_counter.h:56
#define BMI088_ACCEL_RANGE_3_G
perf_counter_t _bad_registers
int reset()
Reset chip.
void update(hrt_abstime timestamp, float x, float y, float z)
uint8_t _register_wait
whoami result
Definition: BMI088.hpp:60
#define BMI088_ACC_INT1_IO_CONF_ACTIVE_HIGH
void Run() override
#define BMI088_ACC_STATUS
#define BMI088_ACCEL_DEFAULT_RANGE_G
#define BMI088_ACC_INT1_INT2_MAP_DATA_INT1_DRDY
int accel_set_sample_rate(float desired_sample_rate_hz)
Set accel sample rate.
#define BMI088_ACC_INT1_IO_CONF
#define BMI088_ACCEL_RANGE_12_G
#define BMI088_ACC_PWR_CTRL
int set_accel_range(unsigned max_g)
Set the BMI088_accel measurement range.
#define BMI088_ACC_PWR_CONF_ACTIVE
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
count the number of times an event occurs
Definition: perf_counter.h:55
perf_counter_t _duplicates
static constexpr float CONSTANTS_ONE_G
Definition: geo.h:51
#define BMI088_ACC_STATUS_DRDY
void set_error_count(uint64_t error_count)
BMI088_accel(int bus, const char *path_accel, uint32_t device, enum Rotation rotation)
#define BMI088_ACC_CONF_ODR_200
#define BMI088_ACC_RANGE
#define BMI088_ACC_INT1_INT2_MAP_DATA
virtual ~BMI088_accel()
#define DIR_READ
Definition: bmp388_spi.cpp:46
#define BMI088_ACCEL_NUM_CHECKED_REGISTERS
void perf_count(perf_counter_t handle)
Count a performance event.
uint8_t _checked_bad[BMI088_ACCEL_NUM_CHECKED_REGISTERS]
#define BMI088_ACC_TEMP_H
void perf_free(perf_counter_t handle)
Free a counter.
#define BMI088_ACC_CONF
void init()
Activates/configures the hardware registers.
void set_temperature(float temperature)
#define perf_alloc(a, b)
Definition: px4io.h:59
Rotation
Enum for board and external compass rotations.
Definition: rotation.h:51
#define BMI088_ACC_SOFTRESET
void write_checked_reg(unsigned reg, uint8_t value)
Write a register in the BMI088_accel, updating _checked_values.
Vector< float, 6 > f(float t, const Matrix< float, 6, 1 > &, const Matrix< float, 3, 1 > &)
Definition: integration.cpp:8
perf_counter_t _sample_perf
virtual int probe()
perf_counter_t _bad_transfers
virtual int init()
PX4Accelerometer _px4_accel
void perf_end(perf_counter_t handle)
End a performance event.
#define BMI088_ACC_INT1_IO_CONF_INT1_OUT
#define BMI088_ACC_CONF_ODR_50
#define BMI088_SOFT_RESET
Definition: BMI088.hpp:47
#define BMI088_ACCEL_DEFAULT_RATE
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
#define BMI088_ACC_PWR_CONF
#define BMI088_ACC_CONF_ODR_800
void set_scale(float scale)
#define BMI088_ACC_CONF_ODR_25
static const uint8_t _checked_registers[BMI088_ACCEL_NUM_CHECKED_REGISTERS]
#define BMI088_ACC_WHO_AM_I
void stop()
Stop automatic measurement.
#define BMI088_ACC_INT1_IO_CONF_PP
uint8_t _whoami
Definition: BMI088.hpp:58
void perf_print_counter(perf_counter_t handle)
Print one performance counter to stdout.
uint64_t perf_event_count(perf_counter_t handle)
Return current event_count.
uint64_t _reset_wait
Definition: BMI088.hpp:61
#define BMI088_ACC_CONF_ODR_400
void check_registers(void)
#define BMI088_ACC_CONF_ODR_100
Definition: bst.cpp:62
virtual uint16_t read_reg16(unsigned reg)
#define BMI088_BUS_SPEED
Definition: BMI088.hpp:49
void modify_reg(unsigned reg, uint8_t clearbits, uint8_t setbits)
Modify a register in the BMI088_accel.
#define BMI088_TIMER_REDUCTION
Definition: BMI088.hpp:51
float _accel_last_temperature_copy
Definition: BMI088_gyro.cpp:42
#define OK
Definition: uavcan_main.cpp:71
#define BMI088_ACC_X_L
uint8_t _checked_next
Definition: BMI088.hpp:65
#define BMI088_ACC_CHIP_ID
#define BMI088_ACC_CONF_ODR_12_5
void set_device_type(uint8_t devtype)
#define BMI088_ACCEL_RANGE_6_G
#define BMI088_ACC_CONF_ODR_1600
void print_registers()
#define DRV_DEVTYPE_BMI088
Definition: drv_sensor.h:117
uint8_t _checked_values[BMI088_ACCEL_NUM_CHECKED_REGISTERS]
void perf_begin(perf_counter_t handle)
Begin a performance event.
#define BMI088_ACC_PWR_CTRL_EN
#define DEVICE_DEBUG(FMT,...)
Definition: Device.hpp:52
__EXPORT hrt_abstime hrt_absolute_time(void)
Get absolute time in [us] (does not wrap).
void write_reg(unsigned reg, uint8_t value)
Write a register in the BMI088.