mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: added CESC message for logging CAN ESC status
This commit is contained in:
parent
6b95d8d22b
commit
a1ad8fbd80
|
@ -256,6 +256,7 @@ public:
|
|||
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 temperature, uint16_t current_tot);
|
||||
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_Attitude(const Vector3f &targets);
|
||||
void Write_AttitudeView(AP_AHRS_View &ahrs, const Vector3f &targets);
|
||||
void Write_Current();
|
||||
|
|
|
@ -815,6 +815,26 @@ void AP_Logger::Write_ServoStatus(uint64_t time_us, uint8_t id, float position,
|
|||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
/*
|
||||
write ESC status from CAN ESC
|
||||
*/
|
||||
void AP_Logger::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)
|
||||
{
|
||||
const struct log_CESC pkt {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CESC_MSG),
|
||||
time_us : time_us,
|
||||
id : id,
|
||||
error_count : error_count,
|
||||
voltage : voltage,
|
||||
current : current,
|
||||
temperature : temperature,
|
||||
rpm : rpm,
|
||||
power_pct : power_pct
|
||||
};
|
||||
WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
|
||||
// Write a Yaw PID packet
|
||||
void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info)
|
||||
{
|
||||
|
|
|
@ -951,6 +951,18 @@ struct PACKED log_CSRV {
|
|||
uint8_t power_pct;
|
||||
};
|
||||
|
||||
struct PACKED log_CESC {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
uint8_t id;
|
||||
uint32_t error_count;
|
||||
float voltage;
|
||||
float current;
|
||||
float temperature;
|
||||
int32_t rpm;
|
||||
uint8_t power_pct;
|
||||
};
|
||||
|
||||
struct PACKED log_AIRSPEED {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
|
@ -1525,6 +1537,8 @@ struct PACKED log_Arm_Disarm {
|
|||
"ESC8", ESC_FMT, ESC_LABELS, ESC_UNITS, ESC_MULTS }, \
|
||||
{ LOG_CSRV_MSG, sizeof(log_CSRV), \
|
||||
"CSRV","QBfffB","TimeUS,Id,Pos,Force,Speed,Pow", "s#---%", "F-0000" }, \
|
||||
{ LOG_CESC_MSG, sizeof(log_CESC), \
|
||||
"CESC","QBIfffiB","TimeUS,Id,ECnt,Voltage,Curr,Temp,RPM,Pow", "s#-vAOq%", "F-000000" }, \
|
||||
{ LOG_COMPASS2_MSG, sizeof(log_Compass), \
|
||||
"MAG2",MAG_FMT, MAG_LABELS, MAG_UNITS, MAG_MULTS }, \
|
||||
{ LOG_COMPASS3_MSG, sizeof(log_Compass), \
|
||||
|
@ -1693,6 +1707,7 @@ enum LogMessages : uint8_t {
|
|||
LOG_ESC7_MSG,
|
||||
LOG_ESC8_MSG,
|
||||
LOG_CSRV_MSG,
|
||||
LOG_CESC_MSG,
|
||||
LOG_BAR2_MSG,
|
||||
LOG_ARSP_MSG,
|
||||
LOG_ATTITUDE_MSG,
|
||||
|
|
Loading…
Reference in New Issue