4 changed files with 89 additions and 1 deletions
@ -0,0 +1,45 @@ |
|||||||
|
#include "AP_Airspeed_SITL.h" |
||||||
|
|
||||||
|
#if AP_AIRSPEED_SITL_ENABLED |
||||||
|
|
||||||
|
#include <AP_Baro/AP_Baro.h> |
||||||
|
#include <SITL/SITL.h> |
||||||
|
|
||||||
|
// return the current differential_pressure in Pascal
|
||||||
|
bool AP_Airspeed_SITL::get_differential_pressure(float &pressure) |
||||||
|
{ |
||||||
|
const uint8_t _instance = get_instance(); |
||||||
|
|
||||||
|
if (_instance >= AIRSPEED_MAX_SENSORS) { |
||||||
|
return false; |
||||||
|
} |
||||||
|
|
||||||
|
pressure = AP::sitl()->state.airspeed_raw_pressure[_instance]; |
||||||
|
|
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
// get last temperature
|
||||||
|
bool AP_Airspeed_SITL::get_temperature(float &temperature) |
||||||
|
{ |
||||||
|
const uint8_t _instance = get_instance(); |
||||||
|
|
||||||
|
if (_instance >= AIRSPEED_MAX_SENSORS) { |
||||||
|
return false; |
||||||
|
} |
||||||
|
|
||||||
|
const auto *sitl = AP::sitl(); |
||||||
|
|
||||||
|
// this was mostly swiped from SIM_Airspeed_DLVR:
|
||||||
|
const float sim_alt = sitl->state.altitude; |
||||||
|
|
||||||
|
float sigma, delta, theta; |
||||||
|
AP_Baro::SimpleAtmosphere(sim_alt * 0.001f, sigma, delta, theta); |
||||||
|
|
||||||
|
// To Do: Add a sensor board temperature offset parameter
|
||||||
|
temperature = (KELVIN_TO_C(SSL_AIR_TEMPERATURE * theta)) + 25.0; |
||||||
|
|
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
#endif // AP_AIRSPEED_SITL_ENABLED
|
@ -0,0 +1,36 @@ |
|||||||
|
/*
|
||||||
|
SITL airspeed backend - a perfect airspeed sensor |
||||||
|
*/ |
||||||
|
#pragma once |
||||||
|
|
||||||
|
#include <AP_HAL/AP_HAL.h> |
||||||
|
#include <AP_HAL/AP_HAL_Boards.h> |
||||||
|
|
||||||
|
#ifndef AP_AIRSPEED_SITL_ENABLED |
||||||
|
#define AP_AIRSPEED_SITL_ENABLED AP_SIM_ENABLED |
||||||
|
#endif |
||||||
|
|
||||||
|
#if AP_AIRSPEED_SITL_ENABLED |
||||||
|
|
||||||
|
#include "AP_Airspeed_Backend.h" |
||||||
|
|
||||||
|
class AP_Airspeed_SITL : public AP_Airspeed_Backend |
||||||
|
{ |
||||||
|
public: |
||||||
|
|
||||||
|
using AP_Airspeed_Backend::AP_Airspeed_Backend; |
||||||
|
|
||||||
|
bool init(void) override { |
||||||
|
return true; |
||||||
|
} |
||||||
|
|
||||||
|
// 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: |
||||||
|
}; |
||||||
|
|
||||||
|
#endif // AP_AIRSPEED_SITL_ENABLED
|
Loading…
Reference in new issue