mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: Split MCU montering into new log message, nan if VCC and servo voltge not avalalbe
This commit is contained in:
parent
16b1bd8b9a
commit
b238ed8dd9
|
@ -343,30 +343,38 @@ void AP_Logger::Write_Power(void)
|
||||||
// encode armed state in bit 3
|
// encode armed state in bit 3
|
||||||
safety_and_armed |= 1U<<2;
|
safety_and_armed |= 1U<<2;
|
||||||
}
|
}
|
||||||
float MCU_temp = 0;
|
const uint64_t now = AP_HAL::micros64();
|
||||||
float MCU_voltage = 0;
|
const struct log_POWR powr_pkt{
|
||||||
float MCU_vmin = 0;
|
|
||||||
float MCU_vmax = 0;
|
|
||||||
#if HAL_WITH_MCU_MONITORING
|
|
||||||
MCU_temp = hal.analogin->mcu_temperature();
|
|
||||||
MCU_voltage = hal.analogin->mcu_voltage();
|
|
||||||
MCU_vmin = hal.analogin->mcu_voltage_min();
|
|
||||||
MCU_vmax = hal.analogin->mcu_voltage_max();
|
|
||||||
#endif
|
|
||||||
const struct log_POWR pkt{
|
|
||||||
LOG_PACKET_HEADER_INIT(LOG_POWR_MSG),
|
LOG_PACKET_HEADER_INIT(LOG_POWR_MSG),
|
||||||
time_us : AP_HAL::micros64(),
|
time_us : now,
|
||||||
|
#if HAL_HAVE_BOARD_VOLTAGE
|
||||||
Vcc : hal.analogin->board_voltage(),
|
Vcc : hal.analogin->board_voltage(),
|
||||||
|
#else
|
||||||
|
Vcc : quiet_nanf(),
|
||||||
|
#endif
|
||||||
|
#if HAL_HAVE_SERVO_VOLTAGE
|
||||||
Vservo : hal.analogin->servorail_voltage(),
|
Vservo : hal.analogin->servorail_voltage(),
|
||||||
|
#else
|
||||||
|
Vservo : quiet_nanf(),
|
||||||
|
#endif
|
||||||
flags : hal.analogin->power_status_flags(),
|
flags : hal.analogin->power_status_flags(),
|
||||||
accumulated_flags : hal.analogin->accumulated_power_status_flags(),
|
accumulated_flags : hal.analogin->accumulated_power_status_flags(),
|
||||||
safety_and_arm : safety_and_armed,
|
safety_and_arm : safety_and_armed,
|
||||||
MCU_temp : MCU_temp,
|
|
||||||
MCU_voltage : MCU_voltage,
|
|
||||||
MCU_voltage_min : MCU_vmin,
|
|
||||||
MCU_voltage_max : MCU_vmax,
|
|
||||||
};
|
};
|
||||||
WriteBlock(&pkt, sizeof(pkt));
|
WriteBlock(&powr_pkt, sizeof(powr_pkt));
|
||||||
|
|
||||||
|
#if HAL_WITH_MCU_MONITORING
|
||||||
|
const struct log_MCU mcu_pkt{
|
||||||
|
LOG_PACKET_HEADER_INIT(LOG_MCU_MSG),
|
||||||
|
time_us : now,
|
||||||
|
MCU_temp : hal.analogin->mcu_temperature(),
|
||||||
|
MCU_voltage : hal.analogin->mcu_voltage(),
|
||||||
|
MCU_voltage_min : hal.analogin->mcu_voltage_min(),
|
||||||
|
MCU_voltage_max : hal.analogin->mcu_voltage_max(),
|
||||||
|
};
|
||||||
|
WriteBlock(&mcu_pkt, sizeof(mcu_pkt));
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -332,6 +332,11 @@ struct PACKED log_POWR {
|
||||||
uint16_t flags;
|
uint16_t flags;
|
||||||
uint16_t accumulated_flags;
|
uint16_t accumulated_flags;
|
||||||
uint8_t safety_and_arm;
|
uint8_t safety_and_arm;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct PACKED log_MCU {
|
||||||
|
LOG_PACKET_HEADER;
|
||||||
|
uint64_t time_us;
|
||||||
float MCU_temp;
|
float MCU_temp;
|
||||||
float MCU_voltage;
|
float MCU_voltage;
|
||||||
float MCU_voltage_min;
|
float MCU_voltage_min;
|
||||||
|
@ -974,10 +979,14 @@ struct PACKED log_VER {
|
||||||
// @Field: Flags: System power flags
|
// @Field: Flags: System power flags
|
||||||
// @Field: AccFlags: Accumulated System power flags; all flags which have ever been set
|
// @Field: AccFlags: Accumulated System power flags; all flags which have ever been set
|
||||||
// @Field: Safety: Hardware Safety Switch status
|
// @Field: Safety: Hardware Safety Switch status
|
||||||
// @Field: MTemp: MCU Temperature
|
|
||||||
// @Field: MVolt: MCU Voltage
|
// @LoggerMessage: MCU
|
||||||
// @Field: MVmin: MCU Voltage min
|
// @Description: MCU voltage and temprature monitering
|
||||||
// @Field: MVmax: MCU Voltage max
|
// @Field: TimeUS: Time since system startup
|
||||||
|
// @Field: MTemp: Temperature
|
||||||
|
// @Field: MVolt: Voltage
|
||||||
|
// @Field: MVmin: Voltage min
|
||||||
|
// @Field: MVmax: Voltage max
|
||||||
|
|
||||||
// @LoggerMessage: RAD
|
// @LoggerMessage: RAD
|
||||||
// @Description: Telemetry radio statistics
|
// @Description: Telemetry radio statistics
|
||||||
|
@ -1249,7 +1258,9 @@ LOG_STRUCTURE_FROM_GPS \
|
||||||
LOG_STRUCTURE_FROM_BARO \
|
LOG_STRUCTURE_FROM_BARO \
|
||||||
LOG_STRUCTURE_FROM_PRECLAND \
|
LOG_STRUCTURE_FROM_PRECLAND \
|
||||||
{ LOG_POWR_MSG, sizeof(log_POWR), \
|
{ LOG_POWR_MSG, sizeof(log_POWR), \
|
||||||
"POWR","QffHHBffff","TimeUS,Vcc,VServo,Flags,AccFlags,Safety,MTemp,MVolt,MVmin,MVmax", "svv---Ovvv", "F00---0000", true }, \
|
"POWR","QffHHB","TimeUS,Vcc,VServo,Flags,AccFlags,Safety", "svv---", "F00---", true }, \
|
||||||
|
{ LOG_MCU_MSG, sizeof(log_MCU), \
|
||||||
|
"MCU","Qffff","TimeUS,MTemp,MVolt,MVmin,MVmax", "sOvvv", "F0000", true }, \
|
||||||
{ LOG_CMD_MSG, sizeof(log_Cmd), \
|
{ LOG_CMD_MSG, sizeof(log_Cmd), \
|
||||||
"CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \
|
"CMD", "QHHHffffLLfB","TimeUS,CTot,CNum,CId,Prm1,Prm2,Prm3,Prm4,Lat,Lng,Alt,Frame", "s-------DUm-", "F-------GG0-" }, \
|
||||||
{ LOG_MAVLINK_COMMAND_MSG, sizeof(log_MAVLink_Command), \
|
{ LOG_MAVLINK_COMMAND_MSG, sizeof(log_MAVLink_Command), \
|
||||||
|
@ -1359,6 +1370,7 @@ enum LogMessages : uint8_t {
|
||||||
LOG_RSSI_MSG,
|
LOG_RSSI_MSG,
|
||||||
LOG_IDS_FROM_BARO,
|
LOG_IDS_FROM_BARO,
|
||||||
LOG_POWR_MSG,
|
LOG_POWR_MSG,
|
||||||
|
LOG_MCU_MSG,
|
||||||
LOG_IDS_FROM_AHRS,
|
LOG_IDS_FROM_AHRS,
|
||||||
LOG_SIMSTATE_MSG,
|
LOG_SIMSTATE_MSG,
|
||||||
LOG_CMD_MSG,
|
LOG_CMD_MSG,
|
||||||
|
|
Loading…
Reference in New Issue