Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Baro/AP_Baro_ICM20789.h
Views: 1798
#pragma once12#include "AP_Baro_Backend.h"34#if AP_BARO_ICM20789_ENABLED56#include <AP_HAL/AP_HAL.h>7#include <AP_HAL/Semaphores.h>8#include <AP_HAL/Device.h>910#ifndef HAL_BARO_ICM20789_I2C_ADDR11// the baro is on a separate I2C address from the IMU, even though in12// the same package13#define HAL_BARO_ICM20789_I2C_ADDR 0x6314#endif1516class AP_Baro_ICM20789 : public AP_Baro_Backend17{18public:19void update() override;2021static AP_Baro_Backend *probe(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, AP_HAL::OwnPtr<AP_HAL::Device> dev_imu);2223private:24AP_Baro_ICM20789(AP_Baro &baro, AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev, AP_HAL::OwnPtr<AP_HAL::Device> dev_imu);2526bool init();27bool send_cmd16(uint16_t cmd);2829bool read_calibration_data(void);3031void convert_data(uint32_t Praw, uint32_t Traw);3233void calculate_conversion_constants(const float p_Pa[3], const float p_LUT[3],34float &A, float &B, float &C);35float get_pressure(uint32_t p_LSB, uint32_t T_LSB);3637bool imu_spi_init(void);38bool imu_i2c_init(void);3940void timer(void);4142// calibration data43int16_t sensor_constants[4];4445uint8_t instance;4647AP_HAL::OwnPtr<AP_HAL::I2CDevice> dev;48AP_HAL::OwnPtr<AP_HAL::Device> dev_imu;4950// time last read command was sent51uint32_t last_measure_us;5253// accumulation structure, protected by _sem54struct {55float tsum;56float psum;57uint32_t count;58} accum;5960// conversion constants. Thanks to invensense for including python61// sample code in the datasheet!62const float p_Pa_calib[3] = {45000.0, 80000.0, 105000.0};63const float LUT_lower = 3.5 * (1U<<20);64const float LUT_upper = 11.5 * (1U<<20);65const float quadr_factor = 1 / 16777216.0;66const float offst_factor = 2048.0;67};6869#endif // AP_BARO_ICM20789_ENABLED707172