mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 07:28:29 -04:00
AP_Logger: add ESC error rate
This commit is contained in:
parent
1c79f22ba2
commit
5436784d38
@ -258,7 +258,7 @@ public:
|
|||||||
void Write_CameraInfo(enum LogMessages msg, const Location ¤t_loc, uint64_t timestamp_us=0);
|
void Write_CameraInfo(enum LogMessages msg, const Location ¤t_loc, uint64_t timestamp_us=0);
|
||||||
void Write_Camera(const Location ¤t_loc, uint64_t timestamp_us=0);
|
void Write_Camera(const Location ¤t_loc, uint64_t timestamp_us=0);
|
||||||
void Write_Trigger(const Location ¤t_loc);
|
void Write_Trigger(const Location ¤t_loc);
|
||||||
void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t esc_temp, uint16_t current_tot, int16_t motor_temp);
|
void Write_ESC(uint8_t id, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t esc_temp, uint16_t current_tot, int16_t motor_temp, float error_rate = 0.0f);
|
||||||
void Write_ServoStatus(uint64_t time_us, uint8_t id, float position, float force, float speed, uint8_t power_pct);
|
void Write_ServoStatus(uint64_t time_us, uint8_t id, float position, float force, float speed, uint8_t power_pct);
|
||||||
void Write_ESCStatus(uint64_t time_us, uint8_t id, uint32_t error_count, float voltage, float current, float temperature, int32_t rpm, uint8_t power_pct);
|
void Write_ESCStatus(uint64_t time_us, uint8_t id, uint32_t error_count, float voltage, float current, float temperature, int32_t rpm, uint8_t power_pct);
|
||||||
void Write_Attitude(const Vector3f &targets);
|
void Write_Attitude(const Vector3f &targets);
|
||||||
|
@ -718,7 +718,7 @@ bool AP_Logger_Backend::Write_Mode(uint8_t mode, const ModeReason reason)
|
|||||||
// current is in centi-amps
|
// current is in centi-amps
|
||||||
// temperature is in centi-degrees Celsius
|
// temperature is in centi-degrees Celsius
|
||||||
// current_tot is in centi-amp hours
|
// current_tot is in centi-amp hours
|
||||||
void AP_Logger::Write_ESC(uint8_t instance, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t esc_temp, uint16_t current_tot, int16_t motor_temp)
|
void AP_Logger::Write_ESC(uint8_t instance, uint64_t time_us, int32_t rpm, uint16_t voltage, uint16_t current, int16_t esc_temp, uint16_t current_tot, int16_t motor_temp, float error_rate)
|
||||||
{
|
{
|
||||||
const struct log_Esc pkt{
|
const struct log_Esc pkt{
|
||||||
LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC_MSG)),
|
LOG_PACKET_HEADER_INIT(uint8_t(LOG_ESC_MSG)),
|
||||||
@ -729,7 +729,8 @@ void AP_Logger::Write_ESC(uint8_t instance, uint64_t time_us, int32_t rpm, uint1
|
|||||||
current : current,
|
current : current,
|
||||||
esc_temp : esc_temp,
|
esc_temp : esc_temp,
|
||||||
current_tot : current_tot,
|
current_tot : current_tot,
|
||||||
motor_temp : motor_temp
|
motor_temp : motor_temp,
|
||||||
|
error_rate : error_rate
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&pkt, sizeof(pkt));
|
||||||
}
|
}
|
||||||
|
@ -712,6 +712,7 @@ struct PACKED log_Esc {
|
|||||||
int16_t esc_temp;
|
int16_t esc_temp;
|
||||||
uint16_t current_tot;
|
uint16_t current_tot;
|
||||||
int16_t motor_temp;
|
int16_t motor_temp;
|
||||||
|
float error_rate;
|
||||||
};
|
};
|
||||||
|
|
||||||
struct PACKED log_CSRV {
|
struct PACKED log_CSRV {
|
||||||
@ -1307,6 +1308,7 @@ struct PACKED log_PSC {
|
|||||||
// @Field: Temp: ESC temperature
|
// @Field: Temp: ESC temperature
|
||||||
// @Field: CTot: current consumed total
|
// @Field: CTot: current consumed total
|
||||||
// @Field: MotTemp: measured motor temperature
|
// @Field: MotTemp: measured motor temperature
|
||||||
|
// @Field: Err: error rate
|
||||||
|
|
||||||
// @LoggerMessage: EV
|
// @LoggerMessage: EV
|
||||||
// @Description: Specifically coded event messages
|
// @Description: Specifically coded event messages
|
||||||
@ -1973,7 +1975,7 @@ struct PACKED log_PSC {
|
|||||||
{ LOG_GPS_RAWS_MSG, sizeof(log_GPS_RAWS), \
|
{ LOG_GPS_RAWS_MSG, sizeof(log_GPS_RAWS), \
|
||||||
"GRXS", "QddfBBBHBBBBB", "TimeUS,prMes,cpMes,doMes,gnss,sv,freq,lock,cno,prD,cpD,doD,trk", "s------------", "F------------" }, \
|
"GRXS", "QddfBBBHBBBBB", "TimeUS,prMes,cpMes,doMes,gnss,sv,freq,lock,cno,prD,cpD,doD,trk", "s------------", "F------------" }, \
|
||||||
{ LOG_ESC_MSG, sizeof(log_Esc), \
|
{ LOG_ESC_MSG, sizeof(log_Esc), \
|
||||||
"ESC", "QBeCCcHc", "TimeUS,Instance,RPM,Volt,Curr,Temp,CTot,MotTemp", "s#qvAO-O", "F-BBBB-B" }, \
|
"ESC", "QBeCCcHcf", "TimeUS,Instance,RPM,Volt,Curr,Temp,CTot,MotTemp,Err", "s#qvAO-O%", "F-BBBB-B-" }, \
|
||||||
{ LOG_CSRV_MSG, sizeof(log_CSRV), \
|
{ LOG_CSRV_MSG, sizeof(log_CSRV), \
|
||||||
"CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000" }, \
|
"CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000" }, \
|
||||||
{ LOG_CESC_MSG, sizeof(log_CESC), \
|
{ LOG_CESC_MSG, sizeof(log_CESC), \
|
||||||
|
Loading…
Reference in New Issue
Block a user