2021-02-23 18:04:06 -04:00
|
|
|
#pragma once
|
|
|
|
|
2023-03-01 02:12:36 -04:00
|
|
|
#include "AP_ESC_Telem_config.h"
|
2021-02-23 18:04:06 -04:00
|
|
|
|
|
|
|
#if HAL_WITH_ESC_TELEM
|
|
|
|
|
|
|
|
class AP_ESC_Telem;
|
|
|
|
|
|
|
|
class AP_ESC_Telem_Backend {
|
|
|
|
public:
|
|
|
|
|
|
|
|
struct TelemetryData {
|
|
|
|
int16_t temperature_cdeg; // centi-degrees C, negative values allowed
|
|
|
|
float voltage; // Volt
|
|
|
|
float current; // Ampere
|
|
|
|
float consumption_mah; // milli-Ampere.hours
|
|
|
|
uint32_t usage_s; // usage seconds
|
|
|
|
int16_t motor_temp_cdeg; // centi-degrees C, negative values allowed
|
2022-01-29 20:18:52 -04:00
|
|
|
uint32_t last_update_ms; // last update time in milliseconds, determines whether active
|
2021-02-23 18:04:06 -04:00
|
|
|
uint16_t types; // telemetry types present
|
|
|
|
uint16_t count; // number of times updated
|
|
|
|
};
|
|
|
|
|
|
|
|
struct RpmData {
|
|
|
|
float rpm; // rpm
|
|
|
|
float prev_rpm; // previous rpm
|
|
|
|
float error_rate; // error rate in percent
|
2023-07-21 14:07:13 -03:00
|
|
|
uint32_t last_update_us; // last update time, greater then 0 means we've gotten data at some point
|
2021-02-23 18:04:06 -04:00
|
|
|
float update_rate_hz;
|
2023-07-21 14:07:13 -03:00
|
|
|
bool data_valid; // if this isn't set to true, then the ESC data should be ignored
|
2021-02-23 18:04:06 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
enum TelemetryType {
|
|
|
|
TEMPERATURE = 1 << 0,
|
|
|
|
MOTOR_TEMPERATURE = 1 << 1,
|
|
|
|
VOLTAGE = 1 << 2,
|
|
|
|
CURRENT = 1 << 3,
|
|
|
|
CONSUMPTION = 1 << 4,
|
2022-10-11 16:34:32 -03:00
|
|
|
USAGE = 1 << 5,
|
|
|
|
TEMPERATURE_EXTERNAL = 1 << 6,
|
|
|
|
MOTOR_TEMPERATURE_EXTERNAL = 1 << 7,
|
2021-02-23 18:04:06 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
|
|
|
|
AP_ESC_Telem_Backend();
|
|
|
|
|
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(AP_ESC_Telem_Backend);
|
2021-02-23 18:04:06 -04:00
|
|
|
|
|
|
|
protected:
|
|
|
|
// callback to update the rpm in the frontend, should be called by the driver when new data is available
|
2022-05-25 08:26:02 -03:00
|
|
|
void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate = 0.0f);
|
2021-02-23 18:04:06 -04:00
|
|
|
|
|
|
|
// callback to update the data in the frontend, should be called by the driver when new data is available
|
|
|
|
void update_telem_data(const uint8_t esc_index, const TelemetryData& new_data, const uint16_t data_present_mask);
|
|
|
|
|
|
|
|
private:
|
|
|
|
AP_ESC_Telem* _frontend;
|
|
|
|
};
|
|
|
|
|
2021-05-26 08:09:32 -03:00
|
|
|
#else
|
|
|
|
|
|
|
|
// dummy empty class
|
|
|
|
class AP_ESC_Telem_Backend {
|
|
|
|
public:
|
|
|
|
AP_ESC_Telem_Backend(){};
|
|
|
|
};
|
|
|
|
|
2021-02-23 18:04:06 -04:00
|
|
|
#endif
|