mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-20 14:54:09 -04:00
AP_Servo_Telem: TelemetryData: remove unused stale
and valid
methods
This commit is contained in:
parent
265f5dfad9
commit
5aaebdf746
@ -31,24 +31,12 @@ AP_Servo_Telem::AP_Servo_Telem()
|
||||
_singleton = this;
|
||||
}
|
||||
|
||||
// return true if the data is stale
|
||||
bool AP_Servo_Telem::TelemetryData::stale(uint32_t now_ms) const volatile
|
||||
{
|
||||
return (last_update_ms == 0) || ((now_ms - last_update_ms) > 5000);
|
||||
}
|
||||
|
||||
// return true if the requested types of data are available
|
||||
bool AP_Servo_Telem::TelemetryData::present(const uint16_t type_mask) const volatile
|
||||
{
|
||||
return (valid_types & type_mask) != 0;
|
||||
}
|
||||
|
||||
// return true if the requested types of data are available and not stale
|
||||
bool AP_Servo_Telem::TelemetryData::valid(const uint16_t type_mask) const volatile
|
||||
{
|
||||
return present(type_mask) && !stale(AP_HAL::millis());
|
||||
}
|
||||
|
||||
// record an update to the telemetry data together with timestamp
|
||||
// callback to update the data in the frontend, should be called by the driver when new data is available
|
||||
void AP_Servo_Telem::update_telem_data(const uint8_t servo_index, const TelemetryData& new_data)
|
||||
|
@ -53,14 +53,8 @@ public:
|
||||
};
|
||||
uint16_t valid_types;
|
||||
|
||||
// return true if the data is stale
|
||||
bool stale(uint32_t now_ms) const volatile;
|
||||
|
||||
// return true if the requested types of data are available
|
||||
bool present(const uint16_t type_mask) const volatile;
|
||||
|
||||
// return true if the requested type of data is available and not stale
|
||||
bool valid(const uint16_t type_mask) const volatile;
|
||||
};
|
||||
|
||||
// update at 10Hz to log telemetry
|
||||
|
Loading…
Reference in New Issue
Block a user