AP_InertialSensor_BMI160.h 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119
  1. /*
  2. * Copyright (C) 2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #pragma once
  18. #include <AP_HAL/AP_HAL.h>
  19. #if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
  20. #include "AP_InertialSensor.h"
  21. #include "AP_InertialSensor_Backend.h"
  22. class AP_InertialSensor_BMI160 : public AP_InertialSensor_Backend {
  23. public:
  24. static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
  25. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev);
  26. /**
  27. * Configure the sensors and start reading routine.
  28. */
  29. void start() override;
  30. bool update() override;
  31. private:
  32. AP_InertialSensor_BMI160(AP_InertialSensor &imu,
  33. AP_HAL::OwnPtr<AP_HAL::Device> dev);
  34. /**
  35. * If the macro BMI160_DEBUG is defined, check if there are errors reported
  36. * on the device's error register and panic if so. The implementation is
  37. * empty if the BMI160_DEBUG isn't defined.
  38. */
  39. void _check_err_reg();
  40. /**
  41. * Try to perform initialization of the BMI160 device.
  42. *
  43. * The device semaphore must be taken and released by the caller.
  44. *
  45. * @return true on success, false otherwise.
  46. */
  47. bool _hardware_init();
  48. /**
  49. * Try to initialize this driver.
  50. *
  51. * Do sensor and other required initializations.
  52. *
  53. * @return true on success, false otherwise.
  54. */
  55. bool _init();
  56. /**
  57. * Configure accelerometer sensor. The device semaphore must already be
  58. * taken before calling this function.
  59. *
  60. * @return true on success, false otherwise.
  61. */
  62. bool _configure_accel();
  63. /**
  64. * Configure gyroscope sensor. The device semaphore must already be
  65. * taken before calling this function.
  66. *
  67. * @return true on success, false otherwise.
  68. */
  69. bool _configure_gyro();
  70. /**
  71. * Configure INT1 pin as watermark interrupt pin at the level of one sample
  72. * if using fifo or data-ready pin otherwise.
  73. *
  74. * @return true on success, false otherwise.
  75. */
  76. bool _configure_int1_pin();
  77. /**
  78. * Configure FIFO.
  79. *
  80. * @return true on success, false otherwise.
  81. */
  82. bool _configure_fifo();
  83. /**
  84. * Device periodic callback to read data from the sensors.
  85. */
  86. void _poll_data();
  87. /**
  88. * Read samples from fifo.
  89. */
  90. void _read_fifo();
  91. AP_HAL::OwnPtr<AP_HAL::Device> _dev;
  92. uint8_t _accel_instance;
  93. float _accel_scale;
  94. uint8_t _gyro_instance;
  95. float _gyro_scale;
  96. AP_HAL::DigitalSource *_int1_pin;
  97. };
  98. #endif