5 changed files with 142 additions and 5 deletions
@ -0,0 +1,63 @@ |
|||||||
|
#include "AP_Airspeed_MSP.h" |
||||||
|
|
||||||
|
#if HAL_MSP_AIRSPEED_ENABLED |
||||||
|
|
||||||
|
AP_Airspeed_MSP::AP_Airspeed_MSP(AP_Airspeed &_frontend, uint8_t _instance, uint8_t _msp_instance) : |
||||||
|
AP_Airspeed_Backend(_frontend, _instance), |
||||||
|
msp_instance(_msp_instance) |
||||||
|
{ |
||||||
|
} |
||||||
|
|
||||||
|
// return the current differential_pressure in Pascal
|
||||||
|
bool AP_Airspeed_MSP::get_differential_pressure(float &pressure) |
||||||
|
{ |
||||||
|
WITH_SEMAPHORE(sem); |
||||||
|
if (press_count == 0) { |
||||||
|
return false; |
||||||
|
} |
||||||
|
pressure = sum_pressure/press_count; |
||||||
|
press_count = 0; |
||||||
|
sum_pressure = 0; |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
// get last temperature
|
||||||
|
bool AP_Airspeed_MSP::get_temperature(float &temperature) |
||||||
|
{ |
||||||
|
WITH_SEMAPHORE(sem); |
||||||
|
if (temp_count == 0) { |
||||||
|
return false; |
||||||
|
} |
||||||
|
temperature = sum_temp/temp_count; |
||||||
|
temp_count = 0; |
||||||
|
sum_temp = 0; |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
void AP_Airspeed_MSP::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) |
||||||
|
{ |
||||||
|
if (pkt.instance != msp_instance) { |
||||||
|
// not for us
|
||||||
|
return; |
||||||
|
} |
||||||
|
WITH_SEMAPHORE(sem); |
||||||
|
|
||||||
|
sum_pressure += pkt.pressure; |
||||||
|
press_count++; |
||||||
|
if (press_count > 100) { |
||||||
|
// prevent overflow
|
||||||
|
sum_pressure /= 2; |
||||||
|
press_count /= 2; |
||||||
|
} |
||||||
|
|
||||||
|
sum_temp += pkt.temp*0.01; |
||||||
|
temp_count++; |
||||||
|
if (temp_count > 100) { |
||||||
|
// prevent overflow
|
||||||
|
sum_temp /= 2; |
||||||
|
temp_count /= 2; |
||||||
|
} |
||||||
|
|
||||||
|
} |
||||||
|
|
||||||
|
#endif // HAL_MSP_AIRSPEED_ENABLED
|
@ -0,0 +1,35 @@ |
|||||||
|
/*
|
||||||
|
MSP airspeed backend |
||||||
|
*/ |
||||||
|
#pragma once |
||||||
|
|
||||||
|
#include "AP_Airspeed_Backend.h" |
||||||
|
|
||||||
|
#if HAL_MSP_AIRSPEED_ENABLED |
||||||
|
|
||||||
|
class AP_Airspeed_MSP : public AP_Airspeed_Backend |
||||||
|
{ |
||||||
|
public: |
||||||
|
AP_Airspeed_MSP(AP_Airspeed &airspeed, uint8_t instance, uint8_t msp_instance); |
||||||
|
|
||||||
|
bool init(void) override { |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
void handle_msp(const MSP::msp_airspeed_data_message_t &pkt) override; |
||||||
|
|
||||||
|
// return the current differential_pressure in Pascal
|
||||||
|
bool get_differential_pressure(float &pressure) override; |
||||||
|
|
||||||
|
// temperature not available via analog backend
|
||||||
|
bool get_temperature(float &temperature) override; |
||||||
|
|
||||||
|
private: |
||||||
|
const uint8_t msp_instance; |
||||||
|
float sum_pressure; |
||||||
|
uint8_t press_count; |
||||||
|
float sum_temp; |
||||||
|
uint8_t temp_count; |
||||||
|
}; |
||||||
|
|
||||||
|
#endif // HAL_MSP_AIRSPEED_ENABLED
|
Loading…
Reference in new issue