Skip to content

Commit

Permalink
ArduSub: move logging of compass ERR flags into AP_Compass
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed May 10, 2022
1 parent b0c8fda commit 8a9a856
Show file tree
Hide file tree
Showing 4 changed files with 0 additions and 21 deletions.
2 changes: 0 additions & 2 deletions ArduSub/ArduSub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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),
Expand Down
15 changes: 0 additions & 15 deletions ArduSub/Log.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -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() {}

Expand Down
3 changes: 0 additions & 3 deletions ArduSub/Sub.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
1 change: 0 additions & 1 deletion ArduSub/Sub.h
Original file line number Diff line number Diff line change
Expand Up @@ -410,7 +410,6 @@ class Sub : public AP_Vehicle {
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;
Expand Down

0 comments on commit 8a9a856

Please sign in to comment.