mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Airspeed: Add enabled check to get functions
This commit is contained in:
parent
e82ba228ce
commit
2ff83bea53
@ -755,6 +755,40 @@ bool AP_Airspeed::healthy(uint8_t i) const {
|
|||||||
return ok;
|
return ok;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// return the current airspeed in m/s
|
||||||
|
float AP_Airspeed::get_airspeed(uint8_t i) const {
|
||||||
|
if (!enabled(i)) {
|
||||||
|
// we can't have negative airspeed so sending an obviously invalid value
|
||||||
|
return -1.0;
|
||||||
|
}
|
||||||
|
return state[i].airspeed;
|
||||||
|
}
|
||||||
|
|
||||||
|
// return the unfiltered airspeed in m/s
|
||||||
|
float AP_Airspeed::get_raw_airspeed(uint8_t i) const {
|
||||||
|
if (!enabled(i)) {
|
||||||
|
// we can't have negative airspeed so sending an obviously invalid value
|
||||||
|
return -1.0;
|
||||||
|
}
|
||||||
|
return state[i].raw_airspeed;
|
||||||
|
}
|
||||||
|
|
||||||
|
// return the differential pressure in Pascal for the last airspeed reading
|
||||||
|
float AP_Airspeed::get_differential_pressure(uint8_t i) const {
|
||||||
|
if (!enabled(i)) {
|
||||||
|
return 0.0;
|
||||||
|
}
|
||||||
|
return state[i].last_pressure;
|
||||||
|
}
|
||||||
|
|
||||||
|
// return the current corrected pressure
|
||||||
|
float AP_Airspeed::get_corrected_pressure(uint8_t i) const {
|
||||||
|
if (!enabled(i)) {
|
||||||
|
return 0.0;
|
||||||
|
}
|
||||||
|
return state[i].corrected_pressure;
|
||||||
|
}
|
||||||
|
|
||||||
#else // build type is not appropriate; provide a dummy implementation:
|
#else // build type is not appropriate; provide a dummy implementation:
|
||||||
const AP_Param::GroupInfo AP_Airspeed::var_info[] = { AP_GROUPEND };
|
const AP_Param::GroupInfo AP_Airspeed::var_info[] = { AP_GROUPEND };
|
||||||
|
|
||||||
@ -764,6 +798,8 @@ void AP_Airspeed::calibrate(bool in_startup) {}
|
|||||||
bool AP_Airspeed::use(uint8_t i) const { return false; }
|
bool AP_Airspeed::use(uint8_t i) const { return false; }
|
||||||
bool AP_Airspeed::enabled(uint8_t i) const { return false; }
|
bool AP_Airspeed::enabled(uint8_t i) const { return false; }
|
||||||
bool AP_Airspeed::healthy(uint8_t i) const { return false; }
|
bool AP_Airspeed::healthy(uint8_t i) const { return false; }
|
||||||
|
float AP_Airspeed::get_airspeed(uint8_t i) const { return 0.0; }
|
||||||
|
float AP_Airspeed::get_differential_pressure(uint8_t i) const { return 0.0; }
|
||||||
|
|
||||||
#if HAL_MSP_AIRSPEED_ENABLED
|
#if HAL_MSP_AIRSPEED_ENABLED
|
||||||
void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {}
|
void AP_Airspeed::handle_msp(const MSP::msp_airspeed_data_message_t &pkt) {}
|
||||||
|
@ -73,15 +73,11 @@ public:
|
|||||||
void calibrate(bool in_startup);
|
void calibrate(bool in_startup);
|
||||||
|
|
||||||
// return the current airspeed in m/s
|
// return the current airspeed in m/s
|
||||||
float get_airspeed(uint8_t i) const {
|
float get_airspeed(uint8_t i) const;
|
||||||
return state[i].airspeed;
|
|
||||||
}
|
|
||||||
float get_airspeed(void) const { return get_airspeed(primary); }
|
float get_airspeed(void) const { return get_airspeed(primary); }
|
||||||
|
|
||||||
// return the unfiltered airspeed in m/s
|
// return the unfiltered airspeed in m/s
|
||||||
float get_raw_airspeed(uint8_t i) const {
|
float get_raw_airspeed(uint8_t i) const;
|
||||||
return state[i].raw_airspeed;
|
|
||||||
}
|
|
||||||
float get_raw_airspeed(void) const { return get_raw_airspeed(primary); }
|
float get_raw_airspeed(void) const { return get_raw_airspeed(primary); }
|
||||||
|
|
||||||
// return the current airspeed ratio (dimensionless)
|
// return the current airspeed ratio (dimensionless)
|
||||||
@ -114,9 +110,7 @@ public:
|
|||||||
bool enabled(void) const { return enabled(primary); }
|
bool enabled(void) const { return enabled(primary); }
|
||||||
|
|
||||||
// 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;
|
|
||||||
}
|
|
||||||
float get_differential_pressure(void) const { return get_differential_pressure(primary); }
|
float get_differential_pressure(void) const { return get_differential_pressure(primary); }
|
||||||
|
|
||||||
// update airspeed ratio calibration
|
// update airspeed ratio calibration
|
||||||
@ -173,9 +167,7 @@ public:
|
|||||||
static AP_Airspeed *get_singleton() { return _singleton; }
|
static AP_Airspeed *get_singleton() { return _singleton; }
|
||||||
|
|
||||||
// return the current corrected pressure, public for AP_Periph
|
// return the current corrected pressure, public for AP_Periph
|
||||||
float get_corrected_pressure(uint8_t i) const {
|
float get_corrected_pressure(uint8_t i) const;
|
||||||
return state[i].corrected_pressure;
|
|
||||||
}
|
|
||||||
float get_corrected_pressure(void) const {
|
float get_corrected_pressure(void) const {
|
||||||
return get_corrected_pressure(primary);
|
return get_corrected_pressure(primary);
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user