mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
8df4e0f127
refactor to capture and output slewed rpm values enable with HAL_WITH_ESC_TELEM move notch calculation to front end refactor telemetry data into frontend cope with blended data add mavlink send function log telemetry data in frontend add SITL ESC telemetry record volts, amps and consumption as floats report telemetry transmission errors disable ESC Telemetry inclusion when there is no need for it move ESC_Telem logging to the AP_ESC_Telem class (by amilcar.lucas@iav.de) various cleanups (by amilcar.lucas@iav.de) add support for raw ESC rpm check RPM validity for mavlink output Use const when applicable
35 lines
1.0 KiB
C
35 lines
1.0 KiB
C
#pragma once
|
|
|
|
#include <AP_Logger/LogStructure.h>
|
|
|
|
#define LOG_IDS_FROM_ESC_TELEM \
|
|
LOG_ESC_MSG
|
|
|
|
// @LoggerMessage: ESC
|
|
// @Description: Feedback received from ESCs
|
|
// @Field: TimeUS: microseconds since system startup
|
|
// @Field: Instance: ESC instance number
|
|
// @Field: RPM: reported motor rotation rate
|
|
// @Field: Volt: Perceived input voltage for the ESC
|
|
// @Field: Curr: Perceived current through the ESC
|
|
// @Field: Temp: ESC temperature in centi-degrees C
|
|
// @Field: CTot: current consumed total mAh
|
|
// @Field: MotTemp: measured motor temperature in centi-degrees C
|
|
// @Field: Err: error rate
|
|
struct PACKED log_Esc {
|
|
LOG_PACKET_HEADER;
|
|
uint64_t time_us;
|
|
uint8_t instance;
|
|
int32_t rpm;
|
|
float voltage;
|
|
float current;
|
|
int16_t esc_temp;
|
|
float current_tot;
|
|
int16_t motor_temp;
|
|
float error_rate;
|
|
};
|
|
|
|
#define LOG_STRUCTURE_FROM_ESC_TELEM \
|
|
{ LOG_ESC_MSG, sizeof(log_Esc), \
|
|
"ESC", "QBeffcfcf", "TimeUS,Instance,RPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qvAOaO%", "F-B--BCB-" },
|