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_Airspeed/AP_Airspeed_ASP5033.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415/*16backend driver for airspeed sensor from www.qio-tek.com17I2C ASP5033 sensor18*/1920#include "AP_Airspeed_ASP5033.h"2122#if AP_AIRSPEED_ASP5033_ENABLED2324#include <AP_HAL/I2CDevice.h>2526extern const AP_HAL::HAL &hal;2728#define ASP5033_I2C_ADDR_1 0x6C29#define ASP5033_I2C_ADDR_2 0x6D30#define REG_CMD 0x3031#define REG_PRESS_DATA 0x0632#define REG_TEMP_DATA 0x0933#define REG_PART_ID 0x0134#define REG_PART_ID_SET 0xa435#define REG_SENSOR_READY 0x0836#define REG_WHOAMI_DEFAULT_ID 0X0037#define REG_WHOAMI_RECHECK_ID 0X6638#define CMD_MEASURE 0x0A394041bool AP_Airspeed_ASP5033::init()42{43// probe the sensor, supporting multiple possible I2C addresses44const uint8_t addresses[] = { ASP5033_I2C_ADDR_1, ASP5033_I2C_ADDR_2 };45for (uint8_t address : addresses) {46dev = hal.i2c_mgr->get_device(get_bus(), address);47if (!dev) {48continue;49}5051WITH_SEMAPHORE(dev->get_semaphore());52dev->set_speed(AP_HAL::Device::SPEED_HIGH);53dev->set_retries(2);5455if (!confirm_sensor_id()) {56continue;57}5859dev->set_device_type(uint8_t(DevType::ASP5033));60set_bus_id(dev->get_bus_id());6162dev->register_periodic_callback(1000000UL/80U,63FUNCTOR_BIND_MEMBER(&AP_Airspeed_ASP5033::timer, void));64return true;65}6667// not found68return false;69}7071/*72this sensor has an unusual whoami scheme. The part_id is changeable73via another register. We check the sensor by looking for the74expected behaviour75*/76bool AP_Airspeed_ASP5033::confirm_sensor_id(void)77{78uint8_t part_id;79if (!dev->read_registers(REG_PART_ID_SET, &part_id, 1) ||80( (part_id != REG_WHOAMI_DEFAULT_ID) && (part_id != REG_WHOAMI_RECHECK_ID) ) ) {81return false;82}83if (!dev->write_register(REG_PART_ID_SET, REG_WHOAMI_RECHECK_ID)) {84return false;85}86if (!dev->read_registers(REG_PART_ID, &part_id, 1) ||87part_id != REG_WHOAMI_RECHECK_ID) {88return false;89}90return true;91}929394// read the data from the sensor95void AP_Airspeed_ASP5033::timer()96{97// request a new measurement cycle begin98dev->write_register(REG_CMD, CMD_MEASURE);99100uint8_t status;101if (!dev->read_registers(REG_CMD, &status, 1) ||102(status & REG_SENSOR_READY) == 0) {103// no data ready104return;105}106107// read pressure and temperature as one block108uint8_t data[5];109if (!dev->read_registers(REG_PRESS_DATA, data, sizeof(data))) {110return;111}112113// ADC pressure is signed 24 bit114int32_t press = (data[0]<<24) | (data[1]<<16) | (data[2]<<8);115116// convert back to 24 bit117press >>= 8;118119// k is a shift based on the pressure range of the device. See120// table in the datasheet121constexpr uint8_t k = 7;122constexpr float press_scale = 1.0 / (1U<<k);123124// temperature is 16 bit signed in units of 1/256 C125const int16_t temp = (data[3]<<8) | data[4];126constexpr float temp_scale = 1.0 / 256;127128WITH_SEMAPHORE(sem);129press_sum += press * press_scale;130temp_sum += temp * temp_scale;131press_count++;132temp_count++;133134last_sample_ms = AP_HAL::millis();135}136137138// return the current differential_pressure in Pascal139bool AP_Airspeed_ASP5033::get_differential_pressure(float &pressure)140{141WITH_SEMAPHORE(sem);142143if (AP_HAL::millis() - last_sample_ms > 100) {144return false;145}146147if (press_count == 0) {148pressure = last_pressure;149return true;150}151152last_pressure = pressure = press_sum / press_count;153154press_count = 0;155press_sum = 0;156157return true;158}159160// return the current temperature in degrees C, if available161bool AP_Airspeed_ASP5033::get_temperature(float &temperature)162{163WITH_SEMAPHORE(sem);164165if (AP_HAL::millis() - last_sample_ms > 100) {166return false;167}168if (temp_count == 0) {169temperature = last_temperature;170return true;171}172173last_temperature = temperature = temp_sum / temp_count;174temp_count = 0;175temp_sum = 0;176177return true;178}179180#endif181182183