Browse Source

Plane: log PIDs during QAUTOTUNE twitch

master
Andrew Tridgell 6 years ago
parent
commit
7939f3488b
  1. 8
      ArduPlane/qautotune.cpp
  2. 1
      ArduPlane/qautotune.h

8
ArduPlane/qautotune.cpp

@ -61,5 +61,13 @@ void QAutoTune::Log_Write_Event(enum at_event id) @@ -61,5 +61,13 @@ void QAutoTune::Log_Write_Event(enum at_event 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

1
ArduPlane/qautotune.h

@ -24,6 +24,7 @@ protected: @@ -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 init_z_limits() override;
void Log_Write_Event(enum at_event id) override;
void log_pids() override;
};
#endif // QAUTOTUNE_ENABLED

Loading…
Cancel
Save