mirror of https://github.com/ArduPilot/ardupilot
Blimp: move logging of compass ERR flags into AP_Compass
This commit is contained in:
parent
8a9a856de8
commit
b33fda72fe
|
@ -63,8 +63,6 @@ const AP_Scheduler::Task Blimp::scheduler_tasks[] = {
|
|||
FAST_TASK(update_flight_mode),
|
||||
// update home from EKF if necessary
|
||||
FAST_TASK(update_home_from_EKF),
|
||||
// log sensor health
|
||||
FAST_TASK(Log_Sensor_Health),
|
||||
|
||||
SCHED_TASK(rc_loop, 100, 130, 3),
|
||||
SCHED_TASK(throttle_loop, 50, 75, 6),
|
||||
|
@ -277,8 +275,6 @@ Blimp::Blimp(void)
|
|||
param_loader(var_info),
|
||||
flightmode(&mode_manual)
|
||||
{
|
||||
// init sensor error logging flags
|
||||
sensor_health.compass = true;
|
||||
}
|
||||
|
||||
Blimp blimp;
|
||||
|
|
|
@ -187,11 +187,6 @@ private:
|
|||
return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf;
|
||||
}
|
||||
|
||||
// sensor health for logging
|
||||
struct {
|
||||
uint8_t compass : 1; // true if compass is healthy
|
||||
} sensor_health;
|
||||
|
||||
// Motor Output
|
||||
Fins *motors;
|
||||
|
||||
|
@ -362,7 +357,6 @@ private:
|
|||
void Log_Write_Data(LogDataID id, uint16_t value);
|
||||
void Log_Write_Data(LogDataID id, float value);
|
||||
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max);
|
||||
void Log_Sensor_Health();
|
||||
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
|
||||
void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out);
|
||||
void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z);
|
||||
|
|
|
@ -232,20 +232,6 @@ tuning_max : tune_max
|
|||
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
|
||||
}
|
||||
|
||||
// logs when compass becomes unhealthy
|
||||
void Blimp::Log_Sensor_Health()
|
||||
{
|
||||
if (!should_log(MASK_LOG_ANY)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// check compass
|
||||
if (sensor_health.compass != compass.healthy()) {
|
||||
sensor_health.compass = compass.healthy();
|
||||
AP::logger().Write_Error(LogErrorSubsystem::COMPASS, (sensor_health.compass ? LogErrorCode::ERROR_RESOLVED : LogErrorCode::UNHEALTHY));
|
||||
}
|
||||
}
|
||||
|
||||
struct PACKED log_SysIdD {
|
||||
LOG_PACKET_HEADER;
|
||||
uint64_t time_us;
|
||||
|
@ -518,7 +504,6 @@ void Blimp::Log_Write_Data(LogDataID id, int16_t value) {}
|
|||
void Blimp::Log_Write_Data(LogDataID id, uint16_t value) {}
|
||||
void Blimp::Log_Write_Data(LogDataID id, float value) {}
|
||||
void Blimp::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {}
|
||||
void Blimp::Log_Sensor_Health() {}
|
||||
void Blimp::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {}
|
||||
void Blimp::Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out) {}
|
||||
void Blimp::Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z) {}
|
||||
|
|
Loading…
Reference in New Issue