mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: move logging of compass ERR flags into AP_Compass
This commit is contained in:
parent
336079ddfa
commit
b0c8fda8d4
|
@ -138,8 +138,6 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
||||||
// camera mount's fast update
|
// camera mount's fast update
|
||||||
FAST_TASK_CLASS(AP_Mount, &copter.camera_mount, update_fast),
|
FAST_TASK_CLASS(AP_Mount, &copter.camera_mount, update_fast),
|
||||||
#endif
|
#endif
|
||||||
// log sensor health
|
|
||||||
FAST_TASK(Log_Sensor_Health),
|
|
||||||
FAST_TASK(Log_Video_Stabilisation),
|
FAST_TASK(Log_Video_Stabilisation),
|
||||||
|
|
||||||
SCHED_TASK(rc_loop, 100, 130, 3),
|
SCHED_TASK(rc_loop, 100, 130, 3),
|
||||||
|
@ -743,8 +741,6 @@ Copter::Copter(void)
|
||||||
param_loader(var_info),
|
param_loader(var_info),
|
||||||
flightmode(&mode_stabilize)
|
flightmode(&mode_stabilize)
|
||||||
{
|
{
|
||||||
// init sensor error logging flags
|
|
||||||
sensor_health.compass = true;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
Copter copter;
|
Copter copter;
|
||||||
|
|
|
@ -397,11 +397,6 @@ private:
|
||||||
return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb;
|
return failsafe.radio || battery.has_failsafed() || failsafe.gcs || failsafe.ekf || failsafe.terrain || failsafe.adsb;
|
||||||
}
|
}
|
||||||
|
|
||||||
// sensor health for logging
|
|
||||||
struct {
|
|
||||||
uint8_t compass : 1; // true if compass is healthy
|
|
||||||
} sensor_health;
|
|
||||||
|
|
||||||
// Motor Output
|
// Motor Output
|
||||||
MOTOR_CLASS *motors;
|
MOTOR_CLASS *motors;
|
||||||
const struct AP_Param::GroupInfo *motors_var_info;
|
const struct AP_Param::GroupInfo *motors_var_info;
|
||||||
|
@ -800,7 +795,6 @@ private:
|
||||||
void Log_Write_Data(LogDataID id, uint16_t value);
|
void Log_Write_Data(LogDataID id, uint16_t value);
|
||||||
void Log_Write_Data(LogDataID id, float 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_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max);
|
||||||
void Log_Sensor_Health();
|
|
||||||
void Log_Video_Stabilisation();
|
void Log_Video_Stabilisation();
|
||||||
#if FRAME_CONFIG == HELI_FRAME
|
#if FRAME_CONFIG == HELI_FRAME
|
||||||
void Log_Write_Heli(void);
|
void Log_Write_Heli(void);
|
||||||
|
|
|
@ -220,20 +220,6 @@ void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float t
|
||||||
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
|
logger.WriteBlock(&pkt_tune, sizeof(pkt_tune));
|
||||||
}
|
}
|
||||||
|
|
||||||
// logs when compass becomes unhealthy
|
|
||||||
void Copter::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));
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void Copter::Log_Video_Stabilisation()
|
void Copter::Log_Video_Stabilisation()
|
||||||
{
|
{
|
||||||
if (!should_log(MASK_LOG_VIDEO_STABILISATION)) {
|
if (!should_log(MASK_LOG_VIDEO_STABILISATION)) {
|
||||||
|
@ -596,7 +582,6 @@ void Copter::Log_Write_Data(LogDataID id, int16_t value) {}
|
||||||
void Copter::Log_Write_Data(LogDataID id, uint16_t value) {}
|
void Copter::Log_Write_Data(LogDataID id, uint16_t value) {}
|
||||||
void Copter::Log_Write_Data(LogDataID id, float value) {}
|
void Copter::Log_Write_Data(LogDataID id, float value) {}
|
||||||
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {}
|
void Copter::Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max) {}
|
||||||
void Copter::Log_Sensor_Health() {}
|
|
||||||
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target) {}
|
void Copter::Log_Write_Guided_Position_Target(ModeGuided::SubMode target_type, const Vector3f& pos_target, bool terrain_alt, const Vector3f& vel_target, const Vector3f& accel_target) {}
|
||||||
void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate) {}
|
void Copter::Log_Write_Guided_Attitude_Target(ModeGuided::SubMode target_type, float roll, float pitch, float yaw, const Vector3f &ang_vel, float thrust, float climb_rate) {}
|
||||||
void Copter::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 Copter::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) {}
|
||||||
|
|
Loading…
Reference in New Issue