mirror of https://github.com/ArduPilot/ardupilot
120 lines
3.1 KiB
C++
120 lines
3.1 KiB
C++
/*
|
|
* Copyright (C) 2016 Intel Corporation. All rights reserved.
|
|
*
|
|
* 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 <http://www.gnu.org/licenses/>.
|
|
*/
|
|
#pragma once
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
|
|
|
#include "AP_InertialSensor.h"
|
|
#include "AP_InertialSensor_Backend.h"
|
|
|
|
class AP_InertialSensor_BMI160 : public AP_InertialSensor_Backend {
|
|
public:
|
|
static AP_InertialSensor_Backend *probe(AP_InertialSensor &imu,
|
|
AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev);
|
|
|
|
/**
|
|
* Configure the sensors and start reading routine.
|
|
*/
|
|
void start() override;
|
|
|
|
bool update() override;
|
|
|
|
private:
|
|
AP_InertialSensor_BMI160(AP_InertialSensor &imu,
|
|
AP_HAL::OwnPtr<AP_HAL::Device> dev);
|
|
|
|
/**
|
|
* If the macro BMI160_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 BMI160_DEBUG isn't defined.
|
|
*/
|
|
void _check_err_reg();
|
|
|
|
/**
|
|
* Try to perform initialization of the BMI160 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.
|
|
*/
|
|
bool _configure_accel();
|
|
|
|
/**
|
|
* Configure gyroscope sensor. The device semaphore must already be
|
|
* taken before calling this function.
|
|
*
|
|
* @return true on success, false otherwise.
|
|
*/
|
|
bool _configure_gyro();
|
|
|
|
/**
|
|
* Configure INT1 pin as watermark interrupt pin at the level of one sample
|
|
* if using fifo or data-ready pin otherwise.
|
|
*
|
|
* @return true on success, false otherwise.
|
|
*/
|
|
bool _configure_int1_pin();
|
|
|
|
/**
|
|
* Configure FIFO.
|
|
*
|
|
* @return true on success, false otherwise.
|
|
*/
|
|
bool _configure_fifo();
|
|
|
|
/**
|
|
* Device periodic callback to read data from the sensors.
|
|
*/
|
|
bool _poll_data();
|
|
|
|
/**
|
|
* Read samples from fifo.
|
|
*/
|
|
void _read_fifo();
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::Device> _dev;
|
|
|
|
uint8_t _accel_instance;
|
|
float _accel_scale;
|
|
|
|
uint8_t _gyro_instance;
|
|
float _gyro_scale;
|
|
|
|
AP_HAL::DigitalSource *_int1_pin;
|
|
};
|
|
|
|
#endif
|