Browse Source

Copter: AC_AutoTune writes events itself now

c415-sdk
Peter Barker 5 years ago committed by Randy Mackay
parent
commit
5ece75a09a
  1. 1
      ArduCopter/mode.h
  2. 28
      ArduCopter/mode_autotune.cpp

1
ArduCopter/mode.h

@ -509,7 +509,6 @@ protected:
float get_pilot_desired_climb_rate_cms(void) const override; float get_pilot_desired_climb_rate_cms(void) const override;
void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &yaw_rate_cds) override; void get_pilot_desired_rp_yrate_cd(float &roll_cd, float &pitch_cd, float &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_pids() override; void log_pids() override;
}; };

28
ArduCopter/mode_autotune.cpp

@ -115,34 +115,6 @@ void AutoTune::log_pids()
copter.logger.Write_PID(LOG_PIDY_MSG, copter.attitude_control->get_rate_yaw_pid().get_pid_info()); copter.logger.Write_PID(LOG_PIDY_MSG, copter.attitude_control->get_rate_yaw_pid().get_pid_info());
} }
/*
Write an event packet. This maps from AC_AutoTune event IDs to
copter event IDs
*/
void AutoTune::Log_Write_Event(enum at_event id)
{
const struct {
enum at_event eid;
Log_Event id;
} map[] = {
{ EVENT_AUTOTUNE_INITIALISED, DATA_AUTOTUNE_INITIALISED },
{ EVENT_AUTOTUNE_OFF, DATA_AUTOTUNE_OFF },
{ EVENT_AUTOTUNE_RESTART, DATA_AUTOTUNE_RESTART },
{ EVENT_AUTOTUNE_SUCCESS, DATA_AUTOTUNE_SUCCESS },
{ EVENT_AUTOTUNE_FAILED, DATA_AUTOTUNE_FAILED },
{ EVENT_AUTOTUNE_REACHED_LIMIT, DATA_AUTOTUNE_REACHED_LIMIT },
{ EVENT_AUTOTUNE_PILOT_TESTING, DATA_AUTOTUNE_PILOT_TESTING },
{ EVENT_AUTOTUNE_SAVEDGAINS, DATA_AUTOTUNE_SAVEDGAINS },
};
for (uint8_t i=0; i<ARRAY_SIZE(map); i++) {
if (id == map[i].eid) {
copter.Log_Write_Event(map[i].id);
break;
}
}
}
/* /*
check if we have a good position estimate check if we have a good position estimate
*/ */

Loading…
Cancel
Save