AP_InertialSensor_BMI088.h 2.5 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687
  1. /*
  2. * This file is free software: you can redistribute it and/or modify it
  3. * under the terms of the GNU General Public License as published by the
  4. * Free Software Foundation, either version 3 of the License, or
  5. * (at your option) any later version.
  6. *
  7. * This file is distributed in the hope that it will be useful, but
  8. * WITHOUT ANY WARRANTY; without even the implied warranty of
  9. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  10. * See the GNU General Public License for more details.
  11. *
  12. * You should have received a copy of the GNU General Public License along
  13. * with this program. If not, see <http://www.gnu.org/licenses/>.
  14. */
  15. /*
  16. the BMI088 is unusual as it has separate chip-select for accel and
  17. gyro, which means it needs two Device pointers
  18. */
  19. #pragma once
  20. #include <AP_HAL/AP_HAL.h>
  21. #include "AP_InertialSensor.h"
  22. #include "AP_InertialSensor_Backend.h"
  23. class AP_InertialSensor_BMI088 : public AP_InertialSensor_Backend {
  24. public:
  25. static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
  26. AP_HAL::OwnPtr<AP_HAL::Device> dev_accel,
  27. AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro,
  28. enum Rotation rotation);
  29. /**
  30. * Configure the sensors and start reading routine.
  31. */
  32. void start() override;
  33. bool update() override;
  34. private:
  35. AP_InertialSensor_BMI088(AP_InertialSensor &imu,
  36. AP_HAL::OwnPtr<AP_HAL::Device> dev_accel,
  37. AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro,
  38. enum Rotation rotation);
  39. /*
  40. initialise hardware layer
  41. */
  42. bool accel_init();
  43. bool gyro_init();
  44. /*
  45. initialise driver
  46. */
  47. bool init();
  48. /*
  49. read data from the FIFOs
  50. */
  51. void read_fifo_accel();
  52. void read_fifo_gyro();
  53. /*
  54. read from accelerometer registers, special SPI handling needed
  55. */
  56. bool read_accel_registers(uint8_t reg, uint8_t *data, uint8_t len);
  57. /*
  58. write to an accelerometer register with retries
  59. */
  60. bool write_accel_register(uint8_t reg, uint8_t v);
  61. /*
  62. configure accel registers
  63. */
  64. bool setup_accel_config(void);
  65. AP_HAL::OwnPtr<AP_HAL::Device> dev_accel;
  66. AP_HAL::OwnPtr<AP_HAL::Device> dev_gyro;
  67. uint8_t accel_instance;
  68. uint8_t gyro_instance;
  69. enum Rotation rotation;
  70. uint8_t temperature_counter;
  71. bool done_accel_config;
  72. uint32_t accel_config_count;
  73. };