Browse Source

ArduSub: move logging of compass ERR flags into AP_Compass

apm_2208
Peter Barker 3 years ago committed by Peter Barker
parent
commit
8a9a856de8
  1. 2
      ArduSub/ArduSub.cpp
  2. 15
      ArduSub/Log.cpp
  3. 3
      ArduSub/Sub.cpp
  4. 1
      ArduSub/Sub.h

2
ArduSub/ArduSub.cpp

@ -68,8 +68,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { @@ -68,8 +68,6 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
// camera mount's fast update
FAST_TASK_CLASS(AP_Mount, &sub.camera_mount, update_fast),
#endif
// log sensor health
FAST_TASK(Log_Sensor_Health),
SCHED_TASK(fifty_hz_loop, 50, 75, 3),
SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6),

15
ArduSub/Log.cpp

@ -168,20 +168,6 @@ void Sub::Log_Write_Data(LogDataID id, float value) @@ -168,20 +168,6 @@ void Sub::Log_Write_Data(LogDataID id, float value)
}
}
// logs when compass becomes unhealthy
void Sub::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_GuidedTarget {
LOG_PACKET_HEADER;
uint64_t time_us;
@ -320,7 +306,6 @@ void Sub::Log_Write_Data(LogDataID id, uint32_t value) {} @@ -320,7 +306,6 @@ void Sub::Log_Write_Data(LogDataID id, uint32_t value) {}
void Sub::Log_Write_Data(LogDataID id, int16_t value) {}
void Sub::Log_Write_Data(LogDataID id, uint16_t value) {}
void Sub::Log_Write_Data(LogDataID id, float value) {}
void Sub::Log_Sensor_Health() {}
void Sub::Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target) {}
void Sub::Log_Write_Vehicle_Startup_Messages() {}

3
ArduSub/Sub.cpp

@ -39,9 +39,6 @@ Sub::Sub() @@ -39,9 +39,6 @@ Sub::Sub()
circle_nav(inertial_nav, ahrs_view, pos_control),
param_loader(var_info)
{
// init sensor error logging flags
sensor_health.compass = true;
#if CONFIG_HAL_BOARD != HAL_BOARD_SITL
failsafe.pilot_input = true;
#endif

1
ArduSub/Sub.h

@ -410,7 +410,6 @@ private: @@ -410,7 +410,6 @@ private:
void Log_Write_Data(LogDataID id, int16_t value);
void Log_Write_Data(LogDataID id, uint16_t value);
void Log_Write_Data(LogDataID id, float value);
void Log_Sensor_Health();
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
void Log_Write_Vehicle_Startup_Messages();
void load_parameters(void) override;

Loading…
Cancel
Save