mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
Plane: added AETR log message
this makes debugging mixers much easier
This commit is contained in:
parent
8e6fa0a707
commit
0ebc7b5122
@ -439,6 +439,32 @@ void Plane::Log_Arm_Disarm() {
|
||||
DataFlash.WriteCriticalBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
|
||||
struct PACKED log_AETR {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
int16_t aileron;
|
||||
int16_t elevator;
|
||||
int16_t throttle;
|
||||
int16_t rudder;
|
||||
int16_t flap;
|
||||
};
|
||||
|
||||
void Plane::Log_Write_AETR()
|
||||
{
|
||||
struct log_AETR pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_AETR_MSG)
|
||||
,time_us : AP_HAL::micros64()
|
||||
,aileron : SRV_Channels::get_output_scaled(SRV_Channel::k_aileron)
|
||||
,elevator : SRV_Channels::get_output_scaled(SRV_Channel::k_elevator)
|
||||
,throttle : SRV_Channels::get_output_scaled(SRV_Channel::k_throttle)
|
||||
,rudder : SRV_Channels::get_output_scaled(SRV_Channel::k_rudder)
|
||||
,flap : SRV_Channels::get_output_scaled(SRV_Channel::k_flap_auto)
|
||||
};
|
||||
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
|
||||
void Plane::Log_Write_GPS(uint8_t instance)
|
||||
{
|
||||
if (!ahrs.have_ekf_logging()) {
|
||||
@ -458,6 +484,7 @@ void Plane::Log_Write_RC(void)
|
||||
if (rssi.enabled()) {
|
||||
DataFlash.Log_Write_RSSI(rssi);
|
||||
}
|
||||
Log_Write_AETR();
|
||||
}
|
||||
|
||||
void Plane::Log_Write_Baro(void)
|
||||
@ -530,6 +557,8 @@ const struct LogStructure Plane::log_structure[] = {
|
||||
"PIQY", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
{ LOG_PIQA_MSG, sizeof(log_PID), \
|
||||
"PIQA", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
{ LOG_AETR_MSG, sizeof(log_AETR), \
|
||||
"AETR", "Qhhhhh", "TimeUS,Ail,Elev,Thr,Rudd,Flap" }, \
|
||||
};
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
|
@ -846,6 +846,7 @@ private:
|
||||
void Log_Write_Home_And_Origin();
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void Log_Write_AOA_SSA();
|
||||
void Log_Write_AETR();
|
||||
void Log_Read(uint16_t log_num, int16_t start_page, int16_t end_page);
|
||||
|
||||
void load_parameters(void);
|
||||
|
@ -146,6 +146,7 @@ enum log_messages {
|
||||
LOG_PIQP_MSG,
|
||||
LOG_PIQY_MSG,
|
||||
LOG_PIQA_MSG,
|
||||
LOG_AETR_MSG,
|
||||
};
|
||||
|
||||
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
||||
|
Loading…
Reference in New Issue
Block a user