diff --git a/libraries/AP_Logger/AP_Logger.cpp b/libraries/AP_Logger/AP_Logger.cpp index 15dbd9163e..50e3b37c59 100644 --- a/libraries/AP_Logger/AP_Logger.cpp +++ b/libraries/AP_Logger/AP_Logger.cpp @@ -12,6 +12,7 @@ #include #include #include +#include AP_Logger *AP_Logger::_singleton; diff --git a/libraries/AP_Logger/AP_Logger.h b/libraries/AP_Logger/AP_Logger.h index 8b4d6ac428..133d06a17d 100644 --- a/libraries/AP_Logger/AP_Logger.h +++ b/libraries/AP_Logger/AP_Logger.h @@ -54,16 +54,11 @@ #define REPLAY_LOG_NEW_MSG_MAX 230 #define REPLAY_LOG_NEW_MSG_MIN 220 -#include #include -#include -#include #include #include #include #include -#include -#include #include #include @@ -71,8 +66,6 @@ #include "LoggerMessageWriter.h" class AP_Logger_Backend; -class AP_AHRS; -class AP_AHRS_View; // do not do anything here apart from add stuff; maintaining older // entries means log analysis is easier @@ -313,7 +306,7 @@ public: const AP_Mission::Mission_Command &cmd); void Write_RallyPoint(uint8_t total, uint8_t sequence, - const RallyLocation &rally_point); + const class RallyLocation &rally_point); void Write_SRTL(bool active, uint16_t num_points, uint16_t max_points, uint8_t action, const Vector3f& point); void Write_Winch(bool healthy, bool thread_end, bool moving, bool clutch, uint8_t mode, float desired_length, float length, float desired_rate, uint16_t tension, float voltage, int8_t temp); void Write_PSCN(float pos_target, float pos, float vel_desired, float vel_target, float vel, float accel_desired, float accel_target, float accel); @@ -328,7 +321,7 @@ public: void WriteCritical(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...); void WriteV(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, va_list arg_list, bool is_critical=false, bool is_streaming=false); - void Write_PID(uint8_t msg_type, const AP_PIDInfo &info); + void Write_PID(uint8_t msg_type, const class AP_PIDInfo &info); // returns true if logging of a message should be attempted bool should_log(uint32_t mask) const; diff --git a/libraries/AP_Logger/AP_Logger_Backend.cpp b/libraries/AP_Logger/AP_Logger_Backend.cpp index 12abc9e0e2..1eb25a11cb 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.cpp +++ b/libraries/AP_Logger/AP_Logger_Backend.cpp @@ -5,6 +5,7 @@ #include "AP_Common/AP_FWVersion.h" #include #include +#include extern const AP_HAL::HAL& hal; diff --git a/libraries/AP_Logger/AP_Logger_Backend.h b/libraries/AP_Logger/AP_Logger_Backend.h index 58d77c46c4..1590435ad8 100644 --- a/libraries/AP_Logger/AP_Logger_Backend.h +++ b/libraries/AP_Logger/AP_Logger_Backend.h @@ -2,6 +2,8 @@ #include "AP_Logger.h" +#include + class LoggerMessageWriter_DFLogStart; #define MAX_LOG_FILES 500 @@ -118,7 +120,7 @@ public: bool Write_EntireMission(); bool Write_RallyPoint(uint8_t total, uint8_t sequence, - const RallyLocation &rally_point); + const class RallyLocation &rally_point); bool Write_Rally(); bool Write_Format(const struct LogStructure *structure); bool Write_Message(const char *message); diff --git a/libraries/AP_Logger/LogFile.cpp b/libraries/AP_Logger/LogFile.cpp index 45a9e0b391..eb135f6f2c 100644 --- a/libraries/AP_Logger/LogFile.cpp +++ b/libraries/AP_Logger/LogFile.cpp @@ -6,6 +6,9 @@ #include #include #include +#include +#include +#include #include "AP_Logger.h" #include "AP_Logger_File.h" diff --git a/libraries/AP_Logger/LoggerMessageWriter.h b/libraries/AP_Logger/LoggerMessageWriter.h index 977643f647..3869a0228a 100644 --- a/libraries/AP_Logger/LoggerMessageWriter.h +++ b/libraries/AP_Logger/LoggerMessageWriter.h @@ -1,6 +1,7 @@ #pragma once #include "AP_Logger_Backend.h" +#include class LoggerMessageWriter { public: