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.cpp
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AP_ESC_Telem.h"16#include <AP_HAL/AP_HAL.h>17#include <GCS_MAVLink/GCS.h>18#include <AP_Logger/AP_Logger.h>1920#if HAL_WITH_ESC_TELEM2122#include <AP_BoardConfig/AP_BoardConfig.h>23#include <AP_TemperatureSensor/AP_TemperatureSensor_config.h>2425#include <AP_Math/AP_Math.h>2627//#define ESC_TELEM_DEBUG2829#define ESC_RPM_CHECK_TIMEOUT_US 210000UL // timeout for motor running validity3031extern const AP_HAL::HAL& hal;3233// table of user settable parameters34const AP_Param::GroupInfo AP_ESC_Telem::var_info[] = {3536// @Param: _MAV_OFS37// @DisplayName: ESC Telemetry mavlink offset38// @Description: Offset to apply to ESC numbers when reporting as ESC_TELEMETRY packets over MAVLink. This allows high numbered motors to be displayed as low numbered ESCs for convenience on GCS displays. A value of 4 would send ESC on output 5 as ESC number 1 in ESC_TELEMETRY packets39// @Increment: 140// @Range: 0 3141// @User: Standard42AP_GROUPINFO("_MAV_OFS", 1, AP_ESC_Telem, mavlink_offset, 0),4344AP_GROUPEND45};4647AP_ESC_Telem::AP_ESC_Telem()48{49if (_singleton) {50AP_HAL::panic("Too many AP_ESC_Telem instances");51}52_singleton = this;53#if !defined(IOMCU_FW)54AP_Param::setup_object_defaults(this, var_info);55#endif56}5758// return the average motor RPM59float AP_ESC_Telem::get_average_motor_rpm(uint32_t servo_channel_mask) const60{61float rpm_avg = 0.0f;62uint8_t valid_escs = 0;6364// average the rpm of each motor65for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {66if (BIT_IS_SET(servo_channel_mask,i)) {67float rpm;68if (get_rpm(i, rpm)) {69rpm_avg += rpm;70valid_escs++;71}72}73}7475if (valid_escs > 0) {76rpm_avg /= valid_escs;77}7879return rpm_avg;80}8182// return all the motor frequencies in Hz for dynamic filtering83uint8_t AP_ESC_Telem::get_motor_frequencies_hz(uint8_t nfreqs, float* freqs) const84{85uint8_t valid_escs = 0;8687// average the rpm of each motor as reported by BLHeli and convert to Hz88for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS && valid_escs < nfreqs; i++) {89float rpm;90if (get_rpm(i, rpm)) {91freqs[valid_escs++] = rpm * (1.0f / 60.0f);92} else if (was_rpm_data_ever_reported(_rpm_data[i])) {93// if we have ever received data on an ESC, mark it as valid but with no data94// this prevents large frequency shifts when ESCs disappear95freqs[valid_escs++] = 0.0f;96}97}9899return MIN(valid_escs, nfreqs);100}101102// get mask of ESCs that sent valid telemetry and/or rpm data in the last103// ESC_TELEM_DATA_TIMEOUT_MS/ESC_RPM_DATA_TIMEOUT_US104uint32_t AP_ESC_Telem::get_active_esc_mask() const {105uint32_t ret = 0;106const uint32_t now = AP_HAL::millis();107uint32_t now_us = AP_HAL::micros();108for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {109if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) {110// have never seen telem from this ESC111continue;112}113if (_telem_data[i].stale(now)114&& !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) {115continue;116}117ret |= (1U << i);118}119return ret;120}121122// return an active ESC for the purposes of reporting (e.g. in the OSD)123uint8_t AP_ESC_Telem::get_max_rpm_esc() const124{125uint32_t ret = 0;126float max_rpm = 0;127const uint32_t now = AP_HAL::millis();128const uint32_t now_us = AP_HAL::micros();129for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {130if (_telem_data[i].last_update_ms == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) {131// have never seen telem from this ESC132continue;133}134if (_telem_data[i].stale(now)135&& !rpm_data_within_timeout(_rpm_data[i], now_us, ESC_RPM_DATA_TIMEOUT_US)) {136continue;137}138if (_rpm_data[i].rpm > max_rpm) {139max_rpm = _rpm_data[i].rpm;140ret = i;141}142}143return ret;144}145146// return number of active ESCs present147uint8_t AP_ESC_Telem::get_num_active_escs() const {148uint32_t active = get_active_esc_mask();149return __builtin_popcount(active);150}151152// return the whether all the motors in servo_channel_mask are running153bool AP_ESC_Telem::are_motors_running(uint32_t servo_channel_mask, float min_rpm, float max_rpm) const154{155const uint32_t now = AP_HAL::micros();156157for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {158if (BIT_IS_SET(servo_channel_mask, i)) {159const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[i];160// we choose a relatively strict measure of health so that failsafe actions can rely on the results161if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_CHECK_TIMEOUT_US)) {162return false;163}164if (rpmdata.rpm < min_rpm) {165return false;166}167if ((max_rpm > 0) && (rpmdata.rpm > max_rpm)) {168return false;169}170}171}172return true;173}174175// is telemetry active for the provided channel mask176bool AP_ESC_Telem::is_telemetry_active(uint32_t servo_channel_mask) const177{178for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {179if (BIT_IS_SET(servo_channel_mask, i)) {180// no data received181if (get_last_telem_data_ms(i) == 0 && !was_rpm_data_ever_reported(_rpm_data[i])) {182return false;183}184}185}186return true;187}188189// get an individual ESC's slewed rpm if available, returns true on success190bool AP_ESC_Telem::get_rpm(uint8_t esc_index, float& rpm) const191{192if (esc_index >= ESC_TELEM_MAX_ESCS) {193return false;194}195196const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index];197198if (is_zero(rpmdata.update_rate_hz)) {199return false;200}201202const uint32_t now = AP_HAL::micros();203if (rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) {204const float slew = MIN(1.0f, (now - rpmdata.last_update_us) * rpmdata.update_rate_hz * (1.0f / 1e6f));205rpm = (rpmdata.prev_rpm + (rpmdata.rpm - rpmdata.prev_rpm) * slew);206207#if AP_SCRIPTING_ENABLED208if ((1U<<esc_index) & rpm_scale_mask) {209rpm *= rpm_scale_factor[esc_index];210}211#endif212213return true;214}215return false;216}217218// get an individual ESC's raw rpm if available, returns true on success219bool AP_ESC_Telem::get_raw_rpm(uint8_t esc_index, float& rpm) const220{221if (esc_index >= ESC_TELEM_MAX_ESCS) {222return false;223}224225const volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index];226227const uint32_t now = AP_HAL::micros();228229if (!rpm_data_within_timeout(rpmdata, now, ESC_RPM_DATA_TIMEOUT_US)) {230return false;231}232233rpm = rpmdata.rpm;234return true;235}236237// get an individual ESC's temperature in centi-degrees if available, returns true on success238bool AP_ESC_Telem::get_temperature(uint8_t esc_index, int16_t& temp) const239{240if (esc_index >= ESC_TELEM_MAX_ESCS) {241return false;242}243244const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];245if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL)) {246return false;247}248temp = telemdata.temperature_cdeg;249return true;250}251252// get an individual motor's temperature in centi-degrees if available, returns true on success253bool AP_ESC_Telem::get_motor_temperature(uint8_t esc_index, int16_t& temp) const254{255if (esc_index >= ESC_TELEM_MAX_ESCS) {256return false;257}258259const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];260if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE | AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL)) {261return false;262}263temp = telemdata.motor_temp_cdeg;264return true;265}266267// get the highest ESC temperature in centi-degrees if available, returns true if there is valid data for at least one ESC268bool AP_ESC_Telem::get_highest_temperature(int16_t& temp) const269{270uint8_t valid_escs = 0;271272for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {273int16_t temp_temp;274if (get_temperature(i, temp_temp)) {275temp = MAX(temp, temp_temp);276valid_escs++;277}278}279280return valid_escs > 0;281}282283// get an individual ESC's current in Ampere if available, returns true on success284bool AP_ESC_Telem::get_current(uint8_t esc_index, float& amps) const285{286if (esc_index >= ESC_TELEM_MAX_ESCS) {287return false;288}289290const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];291if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::CURRENT)) {292return false;293}294amps = telemdata.current;295return true;296}297298// get an individual ESC's voltage in Volt if available, returns true on success299bool AP_ESC_Telem::get_voltage(uint8_t esc_index, float& volts) const300{301if (esc_index >= ESC_TELEM_MAX_ESCS) {302return false;303}304305const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];306if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::VOLTAGE)) {307return false;308}309volts = telemdata.voltage;310return true;311}312313// get an individual ESC's energy consumption in milli-Ampere.hour if available, returns true on success314bool AP_ESC_Telem::get_consumption_mah(uint8_t esc_index, float& consumption_mah) const315{316if (esc_index >= ESC_TELEM_MAX_ESCS) {317return false;318}319320const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];321if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION)) {322return false;323}324consumption_mah = telemdata.consumption_mah;325return true;326}327328// get an individual ESC's usage time in seconds if available, returns true on success329bool AP_ESC_Telem::get_usage_seconds(uint8_t esc_index, uint32_t& usage_s) const330{331if (esc_index >= ESC_TELEM_MAX_ESCS) {332return false;333}334335const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];336if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::USAGE)) {337return false;338}339usage_s = telemdata.usage_s;340return true;341}342343#if AP_EXTENDED_ESC_TELEM_ENABLED344// get an individual ESC's input duty cycle if available, returns true on success345bool AP_ESC_Telem::get_input_duty(uint8_t esc_index, uint8_t& input_duty) const346{347if (esc_index >= ESC_TELEM_MAX_ESCS) {348return false;349}350351const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];352if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY)) {353return false;354}355input_duty = telemdata.input_duty;356return true;357}358359// get an individual ESC's output duty cycle if available, returns true on success360bool AP_ESC_Telem::get_output_duty(uint8_t esc_index, uint8_t& output_duty) const361{362if (esc_index >= ESC_TELEM_MAX_ESCS) {363return false;364}365366const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];367if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY)) {368return false;369}370output_duty = telemdata.output_duty;371return true;372}373374// get an individual ESC's status flags if available, returns true on success375bool AP_ESC_Telem::get_flags(uint8_t esc_index, uint32_t& flags) const376{377if (esc_index >= ESC_TELEM_MAX_ESCS) {378return false;379}380381const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];382if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::FLAGS)) {383return false;384}385flags = telemdata.flags;386return true;387}388389// get an individual ESC's percentage of output power if available, returns true on success390bool AP_ESC_Telem::get_power_percentage(uint8_t esc_index, uint8_t& power_percentage) const391{392if (esc_index >= ESC_TELEM_MAX_ESCS) {393return false;394}395396const volatile AP_ESC_Telem_Backend::TelemetryData& telemdata = _telem_data[esc_index];397if (!telemdata.valid(AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE)) {398return false;399}400power_percentage = telemdata.power_percentage;401return true;402}403#endif // AP_EXTENDED_ESC_TELEM_ENABLED404405// send ESC telemetry messages over MAVLink406void AP_ESC_Telem::send_esc_telemetry_mavlink(uint8_t mav_chan)407{408#if HAL_GCS_ENABLED409if (!_have_data) {410// we've never had any data411return;412}413414const uint32_t now = AP_HAL::millis();415const uint32_t now_us = AP_HAL::micros();416417// loop through groups of 4 ESCs418const uint8_t esc_offset = constrain_int16(mavlink_offset, 0, ESC_TELEM_MAX_ESCS-1);419420// ensure we send out partially-full groups:421const uint8_t num_idx = (ESC_TELEM_MAX_ESCS + 3) / 4;422423for (uint8_t idx = 0; idx < num_idx; idx++) {424const uint8_t i = (next_idx + idx) % num_idx;425426// return if no space in output buffer to send mavlink messages427if (!HAVE_PAYLOAD_SPACE((mavlink_channel_t)mav_chan, ESC_TELEMETRY_1_TO_4)) {428// not enough mavlink buffer space, start at this index next time429next_idx = i;430return;431}432433bool all_stale = true;434for (uint8_t j=0; j<4; j++) {435const uint8_t esc_id = (i * 4 + j) + esc_offset;436if (esc_id < ESC_TELEM_MAX_ESCS &&437(!_telem_data[esc_id].stale(now) ||438rpm_data_within_timeout(_rpm_data[esc_id], now_us, ESC_RPM_DATA_TIMEOUT_US))) {439all_stale = false;440break;441}442}443if (all_stale) {444// skip this group of ESCs if no data to send445continue;446}447448449// arrays to hold output450mavlink_esc_telemetry_1_to_4_t s {};451452// fill in output arrays453for (uint8_t j = 0; j < 4; j++) {454const uint8_t esc_id = (i * 4 + j) + esc_offset;455if (esc_id >= ESC_TELEM_MAX_ESCS) {456continue;457}458volatile AP_ESC_Telem_Backend::TelemetryData const &telemdata = _telem_data[esc_id];459460s.temperature[j] = telemdata.temperature_cdeg / 100;461s.voltage[j] = constrain_float(telemdata.voltage * 100.0f, 0, UINT16_MAX);462s.current[j] = constrain_float(telemdata.current * 100.0f, 0, UINT16_MAX);463s.totalcurrent[j] = constrain_float(telemdata.consumption_mah, 0, UINT16_MAX);464float rpmf;465if (get_rpm(esc_id, rpmf)) {466s.rpm[j] = constrain_float(rpmf, 0, UINT16_MAX);467}468s.count[j] = telemdata.count;469}470471// make sure a msg hasn't been extended472static_assert(MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_5_TO_8_LEN &&473MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_9_TO_12_LEN &&474MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_13_TO_16_LEN &&475MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_17_TO_20_LEN &&476MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN &&477MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_21_TO_24_LEN &&478MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_25_TO_28_LEN &&479MAVLINK_MSG_ID_ESC_TELEMETRY_1_TO_4_LEN == MAVLINK_MSG_ID_ESC_TELEMETRY_29_TO_32_LEN,480"telem messages not compatible");481482const mavlink_channel_t chan = (mavlink_channel_t)mav_chan;483// send messages484switch (i) {485case 0:486mavlink_msg_esc_telemetry_1_to_4_send_struct(chan, &s);487break;488case 1:489mavlink_msg_esc_telemetry_5_to_8_send_struct(chan, (const mavlink_esc_telemetry_5_to_8_t *)&s);490break;491case 2:492mavlink_msg_esc_telemetry_9_to_12_send_struct(chan, (const mavlink_esc_telemetry_9_to_12_t *)&s);493break;494case 3:495mavlink_msg_esc_telemetry_13_to_16_send_struct(chan, (const mavlink_esc_telemetry_13_to_16_t *)&s);496break;497#if ESC_TELEM_MAX_ESCS > 16498case 4:499mavlink_msg_esc_telemetry_17_to_20_send_struct(chan, (const mavlink_esc_telemetry_17_to_20_t *)&s);500break;501case 5:502mavlink_msg_esc_telemetry_21_to_24_send_struct(chan, (const mavlink_esc_telemetry_21_to_24_t *)&s);503break;504case 6:505mavlink_msg_esc_telemetry_25_to_28_send_struct(chan, (const mavlink_esc_telemetry_25_to_28_t *)&s);506break;507case 7:508mavlink_msg_esc_telemetry_29_to_32_send_struct(chan, (const mavlink_esc_telemetry_29_to_32_t *)&s);509break;510#endif511}512}513// we checked for all sends without running out of buffer space,514// start at zero next time515next_idx = 0;516517#endif // HAL_GCS_ENABLED518}519520// record an update to the telemetry data together with timestamp521// this should be called by backends when new telemetry values are available522void AP_ESC_Telem::update_telem_data(const uint8_t esc_index, const AP_ESC_Telem_Backend::TelemetryData& new_data, const uint16_t data_mask)523{524// rpm and telemetry data are not protected by a semaphore even though updated from different threads525// all data is per-ESC and only written from the update thread and read by the user thread526// each element is a primitive type and the timestamp is only updated at the end, thus a caller527// can only get slightly more up-to-date information that perhaps they were expecting or might528// read data that has just gone stale - both of these are safe and avoid the overhead of locking529530if (esc_index >= ESC_TELEM_MAX_ESCS || data_mask == 0) {531return;532}533534_have_data = true;535volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[esc_index];536537#if AP_TEMPERATURE_SENSOR_ENABLED538// always allow external data. Block "internal" if external has ever its ever been set externally then ignore normal "internal" updates539const bool has_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL) ||540((data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE) && !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE_EXTERNAL));541542const bool has_motor_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL) ||543((data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE) && !(telemdata.types & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE_EXTERNAL));544#else545const bool has_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::TEMPERATURE);546const bool has_motor_temperature = (data_mask & AP_ESC_Telem_Backend::TelemetryType::MOTOR_TEMPERATURE);547#endif548549if (has_temperature) {550telemdata.temperature_cdeg = new_data.temperature_cdeg;551}552if (has_motor_temperature) {553telemdata.motor_temp_cdeg = new_data.motor_temp_cdeg;554}555if (data_mask & AP_ESC_Telem_Backend::TelemetryType::VOLTAGE) {556telemdata.voltage = new_data.voltage;557}558if (data_mask & AP_ESC_Telem_Backend::TelemetryType::CURRENT) {559telemdata.current = new_data.current;560}561if (data_mask & AP_ESC_Telem_Backend::TelemetryType::CONSUMPTION) {562telemdata.consumption_mah = new_data.consumption_mah;563}564if (data_mask & AP_ESC_Telem_Backend::TelemetryType::USAGE) {565telemdata.usage_s = new_data.usage_s;566}567568#if AP_EXTENDED_ESC_TELEM_ENABLED569if (data_mask & AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY) {570telemdata.input_duty = new_data.input_duty;571}572if (data_mask & AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY) {573telemdata.output_duty = new_data.output_duty;574}575if (data_mask & AP_ESC_Telem_Backend::TelemetryType::FLAGS) {576telemdata.flags = new_data.flags;577}578if (data_mask & AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE) {579telemdata.power_percentage = new_data.power_percentage;580}581#endif //AP_EXTENDED_ESC_TELEM_ENABLED582583#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED584if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STATUS) {585telemdata.edt2_status = merge_edt2_status(telemdata.edt2_status, new_data.edt2_status);586}587if (data_mask & AP_ESC_Telem_Backend::TelemetryType::EDT2_STRESS) {588telemdata.edt2_stress = merge_edt2_stress(telemdata.edt2_stress, new_data.edt2_stress);589}590#endif591592telemdata.count++;593telemdata.types |= data_mask;594telemdata.last_update_ms = AP_HAL::millis();595}596597// record an update to the RPM together with timestamp, this allows the notch values to be slewed598// this should be called by backends when new telemetry values are available599void AP_ESC_Telem::update_rpm(const uint8_t esc_index, const float new_rpm, const float error_rate)600{601if (esc_index >= ESC_TELEM_MAX_ESCS) {602return;603}604605_have_data = true;606607const uint32_t now = MAX(1U ,AP_HAL::micros()); // don't allow a value of 0 in, as we use this as a flag in places608volatile AP_ESC_Telem_Backend::RpmData& rpmdata = _rpm_data[esc_index];609const auto last_update_us = rpmdata.last_update_us;610611rpmdata.prev_rpm = rpmdata.rpm;612rpmdata.rpm = new_rpm;613rpmdata.update_rate_hz = 1.0e6f / constrain_uint32((now - last_update_us), 100, 1000000U*10U); // limit the update rate 0.1Hz to 10KHz614rpmdata.last_update_us = now;615rpmdata.error_rate = error_rate;616rpmdata.data_valid = true;617618#ifdef ESC_TELEM_DEBUG619hal.console->printf("RPM: rate=%.1fhz, rpm=%f)\n", rpmdata.update_rate_hz, new_rpm);620#endif621}622623#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED624625// The following is based on https://github.com/bird-sanctuary/extended-dshot-telemetry.626// For the following part we explain the bits of Extended DShot Telemetry v2 status telemetry:627// - bits 0-3: the "stress level"628// - bit 5: the "error" bit (e.g. the stall event in Bluejay)629// - bit 6: the "warning" bit (e.g. the desync event in Bluejay)630// - bit 7: the "alert" bit (e.g. the demag event in Bluejay)631632// Since logger can read out telemetry values less frequently than they are updated,633// it makes sense to aggregate these status bits, and to collect the maximum observed stress level.634// To reduce the logging rate of the EDT2 messages, we will try to log them only once a new frame comes.635// To track this, we are going to (ab)use bit 15 of the field: 1 means there is something to write.636637// EDTv2 also features separate "stress" messages.638// These come more frequently, and are scaled differently (the allowed range is from 0 to 255),639// so we have to log them separately.640641constexpr uint16_t EDT2_TELEM_UPDATED = 0x8000U;642constexpr uint16_t EDT2_STRESS_0F_MASK = 0xfU;643constexpr uint16_t EDT2_STRESS_FF_MASK = 0xffU;644constexpr uint16_t EDT2_ERROR_MASK = 0x20U;645constexpr uint16_t EDT2_WARNING_MASK = 0x40U;646constexpr uint16_t EDT2_ALERT_MASK = 0x80U;647constexpr uint16_t EDT2_ALL_BITS = EDT2_ERROR_MASK | EDT2_WARNING_MASK | EDT2_ALERT_MASK;648649#define EDT2_HAS_NEW_DATA(status) bool((status) & EDT2_TELEM_UPDATED)650#define EDT2_STRESS_FROM_STATUS(status) uint8_t((status) & EDT2_STRESS_0F_MASK)651#define EDT2_ERROR_BIT_FROM_STATUS(status) bool((status) & EDT2_ERROR_MASK)652#define EDT2_WARNING_BIT_FROM_STATUS(status) bool((status) & EDT2_WARNING_MASK)653#define EDT2_ALERT_BIT_FROM_STATUS(status) bool((status) & EDT2_ALERT_MASK)654#define EDT2_STRESS_FROM_STRESS(stress) uint8_t((stress) & EDT2_STRESS_FF_MASK)655656uint16_t AP_ESC_Telem::merge_edt2_status(uint16_t old_status, uint16_t new_status)657{658if (EDT2_HAS_NEW_DATA(old_status)) {659new_status = uint16_t(660(old_status & ~EDT2_STRESS_0F_MASK) | // old status except for the stress is preserved661(new_status & EDT2_ALL_BITS) | // all new status bits are included662MAX(old_status & EDT2_STRESS_0F_MASK, new_status & EDT2_STRESS_0F_MASK) // the stress is maxed out663);664}665return EDT2_TELEM_UPDATED | new_status;666}667668uint16_t AP_ESC_Telem::merge_edt2_stress(uint16_t old_stress, uint16_t new_stress)669{670if (EDT2_HAS_NEW_DATA(old_stress)) {671new_stress = uint16_t(672MAX(old_stress & EDT2_STRESS_FF_MASK, new_stress & EDT2_STRESS_FF_MASK) // the stress is maxed out673);674}675return EDT2_TELEM_UPDATED | new_stress;676}677678#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED679680void AP_ESC_Telem::update()681{682#if HAL_LOGGING_ENABLED683AP_Logger *logger = AP_Logger::get_singleton();684const uint64_t now_us64 = AP_HAL::micros64();685686for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {687const volatile AP_ESC_Telem_Backend::RpmData &rpmdata = _rpm_data[i];688volatile AP_ESC_Telem_Backend::TelemetryData &telemdata = _telem_data[i];689// Push received telemetry data into the logging system690if (logger && logger->logging_enabled()) {691if (telemdata.last_update_ms != _last_telem_log_ms[i]692|| rpmdata.last_update_us != _last_rpm_log_us[i]) {693694// Update last log timestamps695_last_telem_log_ms[i] = telemdata.last_update_ms;696_last_rpm_log_us[i] = rpmdata.last_update_us;697698float rpm = AP::logger().quiet_nanf();699get_rpm(i, rpm);700float raw_rpm = AP::logger().quiet_nanf();701get_raw_rpm(i, raw_rpm);702703// Write ESC status messages704// id starts from 0705// rpm, raw_rpm is eRPM (in RPM units)706// voltage is in Volt707// current is in Ampere708// esc_temp is in centi-degrees Celsius709// current_tot is in milli-Ampere hours710// motor_temp is in centi-degrees Celsius711// error_rate is in percentage712const struct log_Esc pkt{713LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC_MSG)),714time_us : now_us64,715instance : i,716rpm : rpm,717raw_rpm : raw_rpm,718voltage : telemdata.voltage,719current : telemdata.current,720esc_temp : telemdata.temperature_cdeg,721current_tot : telemdata.consumption_mah,722motor_temp : telemdata.motor_temp_cdeg,723error_rate : rpmdata.error_rate724};725AP::logger().WriteBlock(&pkt, sizeof(pkt));726727#if AP_EXTENDED_ESC_TELEM_ENABLED728// Write ESC extended status messages729// id: starts from 0730// input duty: duty cycle input to the ESC in percent731// output duty: duty cycle output to the motor in percent732// status flags: manufacurer-specific status flags733const bool has_ext_data = telemdata.types &734(AP_ESC_Telem_Backend::TelemetryType::INPUT_DUTY |735AP_ESC_Telem_Backend::TelemetryType::OUTPUT_DUTY |736AP_ESC_Telem_Backend::TelemetryType::FLAGS |737AP_ESC_Telem_Backend::TelemetryType::POWER_PERCENTAGE);738if (has_ext_data) {739// @LoggerMessage: ESCX740// @Description: ESC extended telemetry data741// @Field: TimeUS: Time since system startup742// @Field: Instance: starts from 0743// @Field: inpct: input duty cycle in percent744// @Field: outpct: output duty cycle in percent745// @Field: flags: manufacturer-specific status flags746// @Field: Pwr: Power percentage747AP::logger().WriteStreaming("ESCX",748"TimeUS,Instance,inpct,outpct,flags,Pwr",749"s" "#" "%" "%" "-" "%",750"F" "-" "-" "-" "-" "-",751"Q" "B" "B" "B" "I" "B",752AP_HAL::micros64(),753i,754telemdata.input_duty,755telemdata.output_duty,756telemdata.flags,757telemdata.power_percentage);758}759#endif //AP_EXTENDED_ESC_TELEM_ENABLED760761#if AP_EXTENDED_DSHOT_TELEM_V2_ENABLED762// Write an EDTv2 message, if there is any update763uint16_t edt2_status = telemdata.edt2_status;764uint16_t edt2_stress = telemdata.edt2_stress;765if (EDT2_HAS_NEW_DATA(edt2_status | edt2_stress)) {766// Could probably be faster/smaller with bitmasking, but not sure767uint8_t status = 0;768if (EDT2_HAS_NEW_DATA(edt2_stress)) {769status |= uint8_t(log_Edt2_Status::HAS_STRESS_DATA);770}771if (EDT2_HAS_NEW_DATA(edt2_status)) {772status |= uint8_t(log_Edt2_Status::HAS_STATUS_DATA);773}774if (EDT2_ALERT_BIT_FROM_STATUS(edt2_status)) {775status |= uint8_t(log_Edt2_Status::ALERT_BIT);776}777if (EDT2_WARNING_BIT_FROM_STATUS(edt2_status)) {778status |= uint8_t(log_Edt2_Status::WARNING_BIT);779}780if (EDT2_ERROR_BIT_FROM_STATUS(edt2_status)) {781status |= uint8_t(log_Edt2_Status::ERROR_BIT);782}783// An EDT2 status message is:784// id: starts from 0785// stress: the current stress which comes from edt2_stress786// max_stress: the maximum stress which comes from edt2_status787// status: the status bits which come from both788const struct log_Edt2 pkt_edt2{789LOG_PACKET_HEADER_INIT(uint8_t(LOG_EDT2_MSG)),790time_us : now_us64,791instance : i,792stress : EDT2_STRESS_FROM_STRESS(edt2_stress),793max_stress : EDT2_STRESS_FROM_STATUS(edt2_status),794status : status,795};796if (AP::logger().WriteBlock_first_succeed(&pkt_edt2, sizeof(pkt_edt2))) {797// Only clean the telem_updated bits if the write succeeded.798// This is important because, if rate limiting is enabled,799// the log-on-change behavior may lose a lot of entries800telemdata.edt2_status &= ~EDT2_TELEM_UPDATED;801telemdata.edt2_stress &= ~EDT2_TELEM_UPDATED;802}803}804#endif // AP_EXTENDED_DSHOT_TELEM_V2_ENABLED805}806}807}808#endif // HAL_LOGGING_ENABLED809810const uint32_t now_us = AP_HAL::micros();811for (uint8_t i = 0; i < ESC_TELEM_MAX_ESCS; i++) {812// Invalidate RPM data if not received for too long813if ((now_us - _rpm_data[i].last_update_us) > ESC_RPM_DATA_TIMEOUT_US) {814_rpm_data[i].data_valid = false;815}816}817}818819bool AP_ESC_Telem::rpm_data_within_timeout(const volatile AP_ESC_Telem_Backend::RpmData &instance, const uint32_t now_us, const uint32_t timeout_us)820{821// easy case, has the time window been crossed so it's invalid822if ((now_us - instance.last_update_us) > timeout_us) {823return false;824}825// we never got a valid data, to it's invalid826if (instance.last_update_us == 0) {827return false;828}829// check if things generally expired on us, this is done to handle time wrapping830return instance.data_valid;831}832833bool AP_ESC_Telem::was_rpm_data_ever_reported(const volatile AP_ESC_Telem_Backend::RpmData &instance)834{835return instance.last_update_us > 0;836}837838#if AP_SCRIPTING_ENABLED839/*840set RPM scale factor from script841*/842void AP_ESC_Telem::set_rpm_scale(const uint8_t esc_index, const float scale_factor)843{844if (esc_index < ESC_TELEM_MAX_ESCS) {845rpm_scale_factor[esc_index] = scale_factor;846rpm_scale_mask |= (1U<<esc_index);847}848}849#endif850851AP_ESC_Telem *AP_ESC_Telem::_singleton = nullptr;852853/*854* Get the AP_ESC_Telem singleton855*/856AP_ESC_Telem *AP_ESC_Telem::get_singleton()857{858return AP_ESC_Telem::_singleton;859}860861namespace AP {862863AP_ESC_Telem &esc_telem()864{865return *AP_ESC_Telem::get_singleton();866}867868};869870#endif // HAL_WITH_ESC_TELEM871872873