Path: blob/master/libraries/AP_Airspeed/AP_Airspeed_MSP.cpp
9623 views
#include "AP_Airspeed_MSP.h"12#if AP_AIRSPEED_MSP_ENABLED34AP_Airspeed_MSP::AP_Airspeed_MSP(AP_Airspeed &_frontend, uint8_t _instance, uint8_t _msp_instance) :5AP_Airspeed_Backend(_frontend, _instance),6msp_instance(_msp_instance)7{8set_bus_id(AP_HAL::Device::make_bus_id(AP_HAL::Device::BUS_TYPE_MSP,0,msp_instance,0));9}1011// return the current differential_pressure in Pascal12bool AP_Airspeed_MSP::get_differential_pressure(float &pressure)13{14WITH_SEMAPHORE(sem);15if (press_count == 0) {16return false;17}18pressure = sum_pressure/press_count;19press_count = 0;20sum_pressure = 0;21return true;22}2324// get last temperature25bool AP_Airspeed_MSP::get_temperature(float &temperature)26{27WITH_SEMAPHORE(sem);28if (temp_count == 0) {29return false;30}31temperature = sum_temp/temp_count;32temp_count = 0;33sum_temp = 0;34return true;35}3637void AP_Airspeed_MSP::handle_msp(const MSP::msp_airspeed_data_message_t &pkt)38{39if (pkt.instance != msp_instance) {40// not for us41return;42}43WITH_SEMAPHORE(sem);4445sum_pressure += pkt.pressure;46press_count++;47if (press_count > 100) {48// prevent overflow49sum_pressure /= 2;50press_count /= 2;51}5253if (pkt.temp == INT16_MIN) {54// invalid temperature55return;56}5758sum_temp += pkt.temp*0.01;59temp_count++;60if (temp_count > 100) {61// prevent overflow62sum_temp /= 2;63temp_count /= 2;64}6566}6768#endif // AP_AIRSPEED_MSP_ENABLED697071