/* * This file is free software: you can redistribute it and/or modify it * under the terms of the GNU General Public License as published by the * Free Software Foundation, either version 3 of the License, or * (at your option) any later version. * * This file is distributed in the hope that it will be useful, but * WITHOUT ANY WARRANTY; without even the implied warranty of * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. * See the GNU General Public License for more details. * * You should have received a copy of the GNU General Public License along * with this program. If not, see . */ #pragma once #include #include #include #include "AP_InertialSensor.h" #include "AP_InertialSensor_Backend.h" #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO #define BMI270_DEFAULT_ROTATION ROTATION_ROLL_180 #else #define BMI270_DEFAULT_ROTATION ROTATION_NONE #endif class AP_InertialSensor_BMI270 : public AP_InertialSensor_Backend { public: static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu, AP_HAL::OwnPtr dev, enum Rotation rotation=BMI270_DEFAULT_ROTATION); static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu, AP_HAL::OwnPtr dev, enum Rotation rotation=BMI270_DEFAULT_ROTATION); /** * Configure the sensors and start reading routine. */ void start() override; bool update() override; private: AP_InertialSensor_BMI270(AP_InertialSensor &imu, AP_HAL::OwnPtr dev, enum Rotation rotation); bool read_registers(uint8_t reg, uint8_t *data, uint8_t len); bool write_register(uint8_t reg, uint8_t v); /** * If the macro BMI270_DEBUG is defined, check if there are errors reported * on the device's error register and panic if so. The implementation is * empty if the BMI270_DEBUG isn't defined. */ void check_err_reg(); /** * Try to perform initialization of the BMI270 device. * * The device semaphore must be taken and released by the caller. * * @return true on success, false otherwise. */ bool hardware_init(); /** * Try to initialize this driver. * * Do sensor and other required initializations. * * @return true on success, false otherwise. */ bool init(); /** * Configure accelerometer sensor. The device semaphore must already be * taken before calling this function. * * @return true on success, false otherwise. */ void configure_accel(); /** * Configure gyroscope sensor. The device semaphore must already be * taken before calling this function. * * @return true on success, false otherwise. */ void configure_gyro(); /** * Reset FIFO. */ void fifo_reset(); /** * Configure FIFO. */ void configure_fifo(); /** * Device periodic callback to read data from the sensors. */ void poll_data(); /** * Read samples from fifo. */ void read_fifo(); void parse_accel_frame(const uint8_t* d); void parse_gyro_frame(const uint8_t* d); AP_HAL::OwnPtr _dev; enum Rotation _rotation; uint8_t _accel_instance; uint8_t _gyro_instance; uint8_t temperature_counter; static const uint8_t maximum_fifo_config_file[]; };