mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 02:28:29 -04:00
Plane: log currently used airspeed
this logs whatever airspeed is being used for flight
This commit is contained in:
parent
e715e47f0c
commit
5631056f10
@ -272,11 +272,15 @@ struct PACKED log_Control_Tuning {
|
||||
int16_t throttle_out;
|
||||
int16_t rudder_out;
|
||||
int16_t throttle_dem;
|
||||
float airspeed_estimate;
|
||||
};
|
||||
|
||||
// Write a control tuning packet. Total length : 22 bytes
|
||||
void Plane::Log_Write_Control_Tuning()
|
||||
{
|
||||
float est_airspeed = 0;
|
||||
ahrs.airspeed_estimate(&est_airspeed);
|
||||
|
||||
struct log_Control_Tuning pkt = {
|
||||
LOG_PACKET_HEADER_INIT(LOG_CTUN_MSG),
|
||||
time_us : AP_HAL::micros64(),
|
||||
@ -286,7 +290,8 @@ void Plane::Log_Write_Control_Tuning()
|
||||
pitch : (int16_t)ahrs.pitch_sensor,
|
||||
throttle_out : (int16_t)SRV_Channels::get_output_scaled(SRV_Channel::k_throttle),
|
||||
rudder_out : (int16_t)SRV_Channels::get_output_scaled(SRV_Channel::k_rudder),
|
||||
throttle_dem : (int16_t)SpdHgt_Controller->get_throttle_demand()
|
||||
throttle_dem : (int16_t)SpdHgt_Controller->get_throttle_demand(),
|
||||
airspeed_estimate : est_airspeed
|
||||
};
|
||||
DataFlash.WriteBlock(&pkt, sizeof(pkt));
|
||||
}
|
||||
@ -530,7 +535,7 @@ const struct LogStructure Plane::log_structure[] = {
|
||||
{ LOG_STARTUP_MSG, sizeof(log_Startup),
|
||||
"STRT", "QBH", "TimeUS,SType,CTot" },
|
||||
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
|
||||
"CTUN", "Qcccchhh", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,ThrDem" },
|
||||
"CTUN", "Qcccchhhf", "TimeUS,NavRoll,Roll,NavPitch,Pitch,ThrOut,RdrOut,ThrDem,Aspd" },
|
||||
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),
|
||||
"NTUN", "Qfcccfff", "TimeUS,WpDist,TargBrg,NavBrg,AltErr,XT,XTi,ArspdErr" },
|
||||
{ LOG_SONAR_MSG, sizeof(log_Sonar),
|
||||
|
Loading…
Reference in New Issue
Block a user