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/LogStructure.h
Views: 1798
#pragma once12#include <AP_Logger/LogStructure.h>3#include "AP_ESC_Telem_config.h"45#define LOG_IDS_FROM_ESC_TELEM \6LOG_ESC_MSG, \7LOG_EDT2_MSG89// @LoggerMessage: ESC10// @Description: Feedback received from ESCs11// @Field: TimeUS: microseconds since system startup12// @Field: Instance: ESC instance number13// @Field: RPM: reported motor rotation rate14// @Field: RawRPM: reported motor rotation rate without slew adjustment15// @Field: Volt: Perceived input voltage for the ESC16// @Field: Curr: Perceived current through the ESC17// @Field: Temp: ESC temperature in centi-degrees C18// @Field: CTot: current consumed total mAh19// @Field: MotTemp: measured motor temperature in centi-degrees C20// @Field: Err: error rate21struct PACKED log_Esc {22LOG_PACKET_HEADER;23uint64_t time_us;24uint8_t instance;25float rpm;26float raw_rpm;27float voltage;28float current;29int16_t esc_temp;30float current_tot;31int16_t motor_temp;32float error_rate;33};3435enum class log_Edt2_Status : uint8_t {36HAS_STRESS_DATA = 1U<<0, // true if the message contains up-to-date stress data37HAS_STATUS_DATA = 1U<<1, // true if the message contains up-to-date status data38ALERT_BIT = 1U<<2, // true if the last status had the "alert" bit (e.g. demag)39WARNING_BIT = 1U<<3, // true if the last status had the "warning" bit (e.g. desync)40ERROR_BIT = 1U<<4, // true if the last status had the "error" bit (e.g. stall)41};424344// @LoggerMessage: EDT245// @Description: Status received from ESCs via Extended DShot telemetry v246// @Field: TimeUS: microseconds since system startup47// @Field: Instance: ESC instance number48// @Field: Stress: current stress level (commutation effort), scaled to [0..255]49// @Field: MaxStress: maximum stress level (commutation effort) since arming, scaled to [0..15]50// @Field: Status: status bits51// @FieldBitmaskEnum: Status: log_Edt2_Status52struct PACKED log_Edt2 {53LOG_PACKET_HEADER;54uint64_t time_us;55uint8_t instance;56uint8_t stress;57uint8_t max_stress;58uint8_t status;59};6061#if HAL_WITH_ESC_TELEM62#define LOG_STRUCTURE_FROM_ESC_TELEM \63{ LOG_ESC_MSG, sizeof(log_Esc), \64"ESC", "QBffffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-00--BCB-" , true }, \65{ LOG_EDT2_MSG, sizeof(log_Edt2), \66"EDT2", "QBBBB", "TimeUS,Instance,Stress,MaxStress,Status", "s#---", "F----" , true },67#else68#define LOG_STRUCTURE_FROM_ESC_TELEM69#endif707172