mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
AP_Airspeed: remove HIL support
This commit is contained in:
parent
1122642f50
commit
77718b1611
@ -395,10 +395,6 @@ float AP_Airspeed::get_pressure(uint8_t i)
|
|||||||
if (!enabled(i)) {
|
if (!enabled(i)) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
if (state[i].hil_set) {
|
|
||||||
state[i].healthy = true;
|
|
||||||
return state[i].hil_pressure;
|
|
||||||
}
|
|
||||||
float pressure = 0;
|
float pressure = 0;
|
||||||
if (sensor[i]) {
|
if (sensor[i]) {
|
||||||
state[i].healthy = sensor[i]->get_differential_pressure(pressure);
|
state[i].healthy = sensor[i]->get_differential_pressure(pressure);
|
||||||
@ -625,17 +621,6 @@ void AP_Airspeed::Log_Airspeed()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void AP_Airspeed::setHIL(float airspeed, float diff_pressure, float temperature)
|
|
||||||
{
|
|
||||||
state[0].raw_airspeed = airspeed;
|
|
||||||
state[0].airspeed = airspeed;
|
|
||||||
state[0].last_pressure = diff_pressure;
|
|
||||||
state[0].last_update_ms = AP_HAL::millis();
|
|
||||||
state[0].hil_pressure = diff_pressure;
|
|
||||||
state[0].hil_set = true;
|
|
||||||
state[0].healthy = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool AP_Airspeed::use(uint8_t i) const
|
bool AP_Airspeed::use(uint8_t i) const
|
||||||
{
|
{
|
||||||
if (!enabled(i) || !param[i].use) {
|
if (!enabled(i) || !param[i].use) {
|
||||||
|
@ -105,11 +105,6 @@ public:
|
|||||||
}
|
}
|
||||||
bool enabled(void) const { return enabled(primary); }
|
bool enabled(void) const { return enabled(primary); }
|
||||||
|
|
||||||
// used by HIL to set the airspeed
|
|
||||||
void set_HIL(float airspeed) {
|
|
||||||
state[primary].airspeed = airspeed;
|
|
||||||
}
|
|
||||||
|
|
||||||
// return the differential pressure in Pascal for the last airspeed reading
|
// return the differential pressure in Pascal for the last airspeed reading
|
||||||
float get_differential_pressure(uint8_t i) const {
|
float get_differential_pressure(uint8_t i) const {
|
||||||
return state[i].last_pressure;
|
return state[i].last_pressure;
|
||||||
@ -132,14 +127,10 @@ public:
|
|||||||
// return true if all enabled sensors are healthy
|
// return true if all enabled sensors are healthy
|
||||||
bool all_healthy(void) const;
|
bool all_healthy(void) const;
|
||||||
|
|
||||||
void setHIL(float pressure) { state[0].healthy=state[0].hil_set=true; state[0].hil_pressure=pressure; }
|
|
||||||
|
|
||||||
// return time in ms of last update
|
// return time in ms of last update
|
||||||
uint32_t last_update_ms(uint8_t i) const { return state[i].last_update_ms; }
|
uint32_t last_update_ms(uint8_t i) const { return state[i].last_update_ms; }
|
||||||
uint32_t last_update_ms(void) const { return last_update_ms(primary); }
|
uint32_t last_update_ms(void) const { return last_update_ms(primary); }
|
||||||
|
|
||||||
void setHIL(float airspeed, float diff_pressure, float temperature);
|
|
||||||
|
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
|
||||||
enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE = 0,
|
enum pitot_tube_order { PITOT_TUBE_ORDER_POSITIVE = 0,
|
||||||
@ -217,11 +208,9 @@ private:
|
|||||||
float last_pressure;
|
float last_pressure;
|
||||||
float filtered_pressure;
|
float filtered_pressure;
|
||||||
float corrected_pressure;
|
float corrected_pressure;
|
||||||
float hil_pressure;
|
|
||||||
uint32_t last_update_ms;
|
uint32_t last_update_ms;
|
||||||
bool use_zero_offset;
|
bool use_zero_offset;
|
||||||
bool healthy;
|
bool healthy;
|
||||||
bool hil_set;
|
|
||||||
|
|
||||||
// state of runtime calibration
|
// state of runtime calibration
|
||||||
struct {
|
struct {
|
||||||
|
Loading…
Reference in New Issue
Block a user