mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: log PIDs during QAUTOTUNE twitch
This commit is contained in:
parent
e279fde505
commit
7939f3488b
@ -61,5 +61,13 @@ void QAutoTune::Log_Write_Event(enum at_event id)
|
|||||||
ev_id);
|
ev_id);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// log VTOL PIDs for during twitch
|
||||||
|
void QAutoTune::log_pids(void)
|
||||||
|
{
|
||||||
|
DataFlash_Class::instance()->Log_Write_PID(LOG_PIQR_MSG, plane.quadplane.attitude_control->get_rate_roll_pid().get_pid_info());
|
||||||
|
DataFlash_Class::instance()->Log_Write_PID(LOG_PIQP_MSG, plane.quadplane.attitude_control->get_rate_pitch_pid().get_pid_info());
|
||||||
|
DataFlash_Class::instance()->Log_Write_PID(LOG_PIQY_MSG, plane.quadplane.attitude_control->get_rate_yaw_pid().get_pid_info());
|
||||||
|
}
|
||||||
|
|
||||||
#endif // QAUTOTUNE_ENABLED
|
#endif // QAUTOTUNE_ENABLED
|
||||||
|
|
||||||
|
@ -24,6 +24,7 @@ protected:
|
|||||||
void get_pilot_desired_rp_yrate_cd(int32_t &roll_cd, int32_t &pitch_cd, int32_t &yaw_rate_cds) override;
|
void get_pilot_desired_rp_yrate_cd(int32_t &roll_cd, int32_t &pitch_cd, int32_t &yaw_rate_cds) override;
|
||||||
void init_z_limits() override;
|
void init_z_limits() override;
|
||||||
void Log_Write_Event(enum at_event id) override;
|
void Log_Write_Event(enum at_event id) override;
|
||||||
|
void log_pids() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif // QAUTOTUNE_ENABLED
|
#endif // QAUTOTUNE_ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user