Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_ESC_Telem/AP_ESC_Telem.h
Views: 1798
#pragma once12#include <AP_HAL/AP_HAL.h>3#include <AP_Param/AP_Param.h>4#include <SRV_Channel/SRV_Channel_config.h>5#include "AP_ESC_Telem_Backend.h"67#if HAL_WITH_ESC_TELEM89#ifndef ESC_TELEM_MAX_ESCS10#define ESC_TELEM_MAX_ESCS NUM_SERVO_CHANNELS11#endif12static_assert(ESC_TELEM_MAX_ESCS > 0, "Cannot have 0 ESC telemetry instances");1314#define ESC_TELEM_DATA_TIMEOUT_MS 5000UL15#define ESC_RPM_DATA_TIMEOUT_US 1000000UL1617class AP_ESC_Telem {18public:19friend class AP_ESC_Telem_Backend;2021AP_ESC_Telem();2223/* Do not allow copies */24CLASS_NO_COPY(AP_ESC_Telem);2526static const struct AP_Param::GroupInfo var_info[];2728static AP_ESC_Telem *get_singleton();2930// get an individual ESC's slewed rpm if available, returns true on success31bool get_rpm(uint8_t esc_index, float& rpm) const;3233// get an individual ESC's raw rpm if available34bool get_raw_rpm(uint8_t esc_index, float& rpm) const;3536// get raw telemetry data, used by IOMCU37const volatile AP_ESC_Telem_Backend::TelemetryData& get_telem_data(uint8_t esc_index) const {38return _telem_data[esc_index];39}4041// return the average motor RPM42float get_average_motor_rpm(uint32_t servo_channel_mask) const;4344// return the average motor RPM45float get_average_motor_rpm() const { return get_average_motor_rpm(0xFFFFFFFF); }4647// determine whether all the motors in servo_channel_mask are running48bool are_motors_running(uint32_t servo_channel_mask, float min_rpm, float max_rpm) const;4950// get an individual ESC's temperature in centi-degrees if available, returns true on success51bool get_temperature(uint8_t esc_index, int16_t& temp) const;5253// get an individual motor's temperature in centi-degrees if available, returns true on success54bool get_motor_temperature(uint8_t esc_index, int16_t& temp) const;5556// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC57bool get_highest_temperature(int16_t& temp) const;5859// get an individual ESC's current in Ampere if available, returns true on success60bool get_current(uint8_t esc_index, float& amps) const;6162// get an individual ESC's usage time in seconds if available, returns true on success63bool get_usage_seconds(uint8_t esc_index, uint32_t& usage_sec) const;6465// get an individual ESC's voltage in Volt if available, returns true on success66bool get_voltage(uint8_t esc_index, float& volts) const;6768// get an individual ESC's consumption in milli-Ampere.hour if available, returns true on success69bool get_consumption_mah(uint8_t esc_index, float& consumption_mah) const;7071#if AP_EXTENDED_ESC_TELEM_ENABLED72// get an individual ESC's input duty cycle if available, returns true on success73bool get_input_duty(uint8_t esc_index, uint8_t& input_duty) const;7475// get an individual ESC's output duty cycle if available, returns true on success76bool get_output_duty(uint8_t esc_index, uint8_t& output_duty) const;7778// get an individual ESC's status flags if available, returns true on success79bool get_flags(uint8_t esc_index, uint32_t& flags) const;8081// get an individual ESC's percentage of output power if available, returns true on success82bool get_power_percentage(uint8_t esc_index, uint8_t& power_percentage) const;83#endif8485// return the average motor frequency in Hz for dynamic filtering86float get_average_motor_frequency_hz(uint32_t servo_channel_mask) const { return get_average_motor_rpm(servo_channel_mask) * (1.0f / 60.0f); };8788// return the average motor frequency in Hz for dynamic filtering89float get_average_motor_frequency_hz() const { return get_average_motor_frequency_hz(0xFFFFFFFF); }9091// return all of the motor frequencies in Hz for dynamic filtering92uint8_t get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) const;9394// get the number of ESCs that sent valid telemetry data in the last ESC_TELEM_DATA_TIMEOUT_MS95uint8_t get_num_active_escs() const;9697// get mask of ESCs that sent valid telemetry data in the last98// ESC_TELEM_DATA_TIMEOUT_MS99uint32_t get_active_esc_mask() const;100101// return an active ESC with the highest RPM for the purposes of reporting (e.g. in the OSD)102uint8_t get_max_rpm_esc() const;103104// return the last time telemetry data was received in ms for the given ESC or 0 if never105uint32_t get_last_telem_data_ms(uint8_t esc_index) const {106if (esc_index >= ESC_TELEM_MAX_ESCS) {return 0;}107return _telem_data[esc_index].last_update_ms;108}109110// send telemetry data to mavlink111void send_esc_telemetry_mavlink(uint8_t mav_chan);112113// update at 10Hz to log telemetry114void update();115116// is rpm telemetry configured for the provided channel mask117bool is_telemetry_active(uint32_t servo_channel_mask) const;118119// callback to update the rpm in the frontend, should be called by the driver when new data is available120// can also be called from scripting121void update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate);122123// callback to update the data in the frontend, should be called by the driver when new data is available124void update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask);125126#if AP_SCRIPTING_ENABLED127/*128set RPM scale factor from script129*/130void set_rpm_scale(const uint8_t esc_index, const float scale_factor);131#endif132133private:134135// helper that validates RPM data136static bool rpm_data_within_timeout (const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us);137static bool was_rpm_data_ever_reported (const volatile AP_ESC_Telem_Backend::RpmData &instance);138139#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED140// helpers that aggregate data in EDTv2 messages141static uint16_t merge_edt2_status(uint16_t old_status, uint16_t new_status);142static uint16_t merge_edt2_stress(uint16_t old_stress, uint16_t new_stress);143#endif144145// rpm data146volatile AP_ESC_Telem_Backend::RpmData _rpm_data[ESC_TELEM_MAX_ESCS];147// telemetry data148volatile AP_ESC_Telem_Backend::TelemetryData _telem_data[ESC_TELEM_MAX_ESCS];149150uint32_t _last_telem_log_ms[ESC_TELEM_MAX_ESCS];151uint32_t _last_rpm_log_us[ESC_TELEM_MAX_ESCS];152uint8_t next_idx;153154#if AP_SCRIPTING_ENABLED155// allow for scaling of RPMs via lua scripts156float rpm_scale_factor[ESC_TELEM_MAX_ESCS];157uint32_t rpm_scale_mask;158#endif159160bool _have_data;161162AP_Int8 mavlink_offset;163164static AP_ESC_Telem *_singleton;165};166167namespace AP {168AP_ESC_Telem &esc_telem();169};170171#endif // HAL_WITH_ESC_TELEM172173174