mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
Plane: added PIQ messages for quadplane PIDs
keep them separate from fixed wing PIDs, so we can watch the interaction between the PIDs in transitions
This commit is contained in:
parent
e3bca10e9a
commit
dd4f56dd98
@ -163,22 +163,23 @@ void Plane::Log_Write_Attitude(void)
|
||||
targets.z = 0; //Plane does not have the concept of navyaw. This is a placeholder.
|
||||
|
||||
DataFlash.Log_Write_Attitude(ahrs, targets);
|
||||
if (quadplane.in_vtol_mode()) {
|
||||
DataFlash.Log_Write_PID(LOG_PIDR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDY_MSG, quadplane.attitude_control->get_rate_yaw_pid().get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDA_MSG, quadplane.pid_accel_z.get_pid_info() );
|
||||
} else {
|
||||
if (quadplane.in_vtol_mode() || quadplane.in_assisted_flight()) {
|
||||
// log quadplane PIDs separately from fixed wing PIDs
|
||||
DataFlash.Log_Write_PID(LOG_PIQR_MSG, quadplane.attitude_control->get_rate_roll_pid().get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIQP_MSG, quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIQY_MSG, quadplane.attitude_control->get_rate_yaw_pid().get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIQA_MSG, quadplane.pid_accel_z.get_pid_info() );
|
||||
}
|
||||
|
||||
DataFlash.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
const DataFlash_Class::PID_Info *landing_info;
|
||||
DataFlash.Log_Write_PID(LOG_PIDR_MSG, rollController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDP_MSG, pitchController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDY_MSG, yawController.get_pid_info());
|
||||
DataFlash.Log_Write_PID(LOG_PIDS_MSG, steerController.get_pid_info());
|
||||
if (flight_stage == AP_Vehicle::FixedWing::FLIGHT_LAND) {
|
||||
landing_info = landing.get_pid_info();
|
||||
if (landing_info != nullptr) { // only log LANDING PID's while in landing
|
||||
DataFlash.Log_Write_PID(LOG_PIDL_MSG, *landing_info);
|
||||
}
|
||||
landing_info = landing.get_pid_info();
|
||||
if (landing_info != nullptr) { // only log LANDING PID's while in landing
|
||||
DataFlash.Log_Write_PID(LOG_PIDL_MSG, *landing_info);
|
||||
}
|
||||
}
|
||||
|
||||
@ -500,6 +501,14 @@ const struct LogStructure Plane::log_structure[] = {
|
||||
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow),
|
||||
"OF", "QBffff", "TimeUS,Qual,flowX,flowY,bodyX,bodyY" },
|
||||
#endif
|
||||
{ LOG_PIQR_MSG, sizeof(log_PID), \
|
||||
"PIQR", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
{ LOG_PIQP_MSG, sizeof(log_PID), \
|
||||
"PIQP", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
{ LOG_PIQY_MSG, sizeof(log_PID), \
|
||||
"PIQY", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
{ LOG_PIQA_MSG, sizeof(log_PID), \
|
||||
"PIQA", "Qffffff", "TimeUS,Des,P,I,D,FF,AFF" }, \
|
||||
};
|
||||
|
||||
#if CLI_ENABLED == ENABLED
|
||||
|
@ -141,7 +141,11 @@ enum log_messages {
|
||||
LOG_QTUN_MSG,
|
||||
LOG_PARAMTUNE_MSG,
|
||||
LOG_THERMAL_MSG,
|
||||
LOG_VARIO_MSG
|
||||
LOG_VARIO_MSG,
|
||||
LOG_PIQR_MSG,
|
||||
LOG_PIQP_MSG,
|
||||
LOG_PIQY_MSG,
|
||||
LOG_PIQA_MSG,
|
||||
};
|
||||
|
||||
#define MASK_LOG_ATTITUDE_FAST (1<<0)
|
||||
|
Loading…
Reference in New Issue
Block a user