mirror of https://github.com/ArduPilot/ardupilot
AP_ESC_Telem: Log RPM and raw RPM values as floats
This commit is contained in:
parent
6ca3f31143
commit
30146affa5
|
@ -502,12 +502,12 @@ void AP_ESC_Telem::update()
|
|||
|
||||
float rpm = 0.0f;
|
||||
get_rpm(i, rpm);
|
||||
float rawrpm = 0.0f;
|
||||
get_raw_rpm(i, rawrpm);
|
||||
float raw_rpm = 0.0f;
|
||||
get_raw_rpm(i, raw_rpm);
|
||||
|
||||
// Write ESC status messages
|
||||
// id starts from 0
|
||||
// rpm is eRPM (rpm * 100)
|
||||
// rpm, raw_rpm is eRPM (in RPM units)
|
||||
// voltage is in Volt
|
||||
// current is in Ampere
|
||||
// esc_temp is in centi-degrees Celsius
|
||||
|
@ -518,8 +518,8 @@ void AP_ESC_Telem::update()
|
|||
LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC_MSG)),
|
||||
time_us : AP_HAL::micros64(),
|
||||
instance : i,
|
||||
rpm : (int32_t) rpm * 100,
|
||||
raw_rpm : (int32_t) rawrpm * 100,
|
||||
rpm : rpm,
|
||||
raw_rpm : raw_rpm,
|
||||
voltage : _telem_data[i].voltage,
|
||||
current : _telem_data[i].current,
|
||||
esc_temp : _telem_data[i].temperature_cdeg,
|
||||
|
|
|
@ -21,8 +21,8 @@ struct PACKED log_Esc {
|
|||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint8_t instance;
|
||||
int32_t rpm;
|
||||
int32_t raw_rpm;
|
||||
float rpm;
|
||||
float raw_rpm;
|
||||
float voltage;
|
||||
float current;
|
||||
int16_t esc_temp;
|
||||
|
@ -33,4 +33,4 @@ struct PACKED log_Esc {
|
|||
|
||||
#define LOG_STRUCTURE_FROM_ESC_TELEM \
|
||||
{ LOG_ESC_MSG, sizeof(log_Esc), \
|
||||
"ESC", "QBeeffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-BB--BCB-" , true },
|
||||
"ESC", "QBffffcfcf", "TimeUS,Instance,RPM,RawRPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qqvAOaO%", "F-00--BCB-" , true },
|
||||
|
|
Loading…
Reference in New Issue