mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_BLHeli: added have_telem_data() API
This commit is contained in:
parent
05f4bf0b32
commit
952a3956a9
@ -1417,6 +1417,7 @@ void AP_BLHeli::read_telemetry_packet(void)
|
|||||||
|
|
||||||
last_telem[last_telem_esc] = td;
|
last_telem[last_telem_esc] = td;
|
||||||
last_telem[last_telem_esc].count++;
|
last_telem[last_telem_esc].count++;
|
||||||
|
received_telem_data = true;
|
||||||
|
|
||||||
AP_Logger *logger = AP_Logger::get_singleton();
|
AP_Logger *logger = AP_Logger::get_singleton();
|
||||||
if (logger && logger->logging_enabled()
|
if (logger && logger->logging_enabled()
|
||||||
|
@ -65,6 +65,11 @@ public:
|
|||||||
// return all of the motor frequencies in Hz for dynamic filtering
|
// return all of the motor frequencies in Hz for dynamic filtering
|
||||||
uint8_t get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) const;
|
uint8_t get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) const;
|
||||||
|
|
||||||
|
// return true if we have received any telemetry data
|
||||||
|
bool have_telem_data(void) const {
|
||||||
|
return received_telem_data;
|
||||||
|
}
|
||||||
|
|
||||||
static AP_BLHeli *get_singleton(void) {
|
static AP_BLHeli *get_singleton(void) {
|
||||||
return _singleton;
|
return _singleton;
|
||||||
}
|
}
|
||||||
@ -228,6 +233,8 @@ private:
|
|||||||
uint8_t num_motors;
|
uint8_t num_motors;
|
||||||
|
|
||||||
struct telem_data last_telem[max_motors];
|
struct telem_data last_telem[max_motors];
|
||||||
|
uint32_t received_telem_data;
|
||||||
|
|
||||||
// last log output to avoid beat frequencies
|
// last log output to avoid beat frequencies
|
||||||
uint32_t last_log_ms[max_motors];
|
uint32_t last_log_ms[max_motors];
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user