AP_Logger: remove unused includes

This commit is contained in:
Peter Barker 2022-07-14 15:48:35 +10:00 committed by Andrew Tridgell
parent 52d9dc1471
commit 659f801650
6 changed files with 11 additions and 10 deletions

View File

@ -12,6 +12,7 @@
#include <AP_InternalError/AP_InternalError.h>
#include <GCS_MAVLink/GCS.h>
#include <AP_BoardConfig/AP_BoardConfig.h>
#include <AP_Rally/AP_Rally.h>
AP_Logger *AP_Logger::_singleton;

View File

@ -54,16 +54,11 @@
#define REPLAY_LOG_NEW_MSG_MAX 230
#define REPLAY_LOG_NEW_MSG_MIN 220
#include <AC_PID/AC_PID.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_AHRS/AP_AHRS.h>
#include <AP_AHRS/AP_AHRS_DCM.h>
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <AP_Mission/AP_Mission.h>
#include <AP_Logger/LogStructure.h>
#include <AP_Motors/AP_Motors.h>
#include <AP_Rally/AP_Rally.h>
#include <AP_Vehicle/ModeReason.h>
#include <stdint.h>
@ -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;

View File

@ -5,6 +5,7 @@
#include "AP_Common/AP_FWVersion.h"
#include <AP_InternalError/AP_InternalError.h>
#include <AP_Scheduler/AP_Scheduler.h>
#include <AP_Rally/AP_Rally.h>
extern const AP_HAL::HAL& hal;

View File

@ -2,6 +2,8 @@
#include "AP_Logger.h"
#include <AP_Common/Bitmask.h>
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);

View File

@ -6,6 +6,9 @@
#include <AP_Math/AP_Math.h>
#include <AP_Param/AP_Param.h>
#include <AP_RSSI/AP_RSSI.h>
#include <RC_Channel/RC_Channel.h>
#include <SRV_Channel/SRV_Channel.h>
#include <AC_PID/AC_PID.h>
#include "AP_Logger.h"
#include "AP_Logger_File.h"

View File

@ -1,6 +1,7 @@
#pragma once
#include "AP_Logger_Backend.h"
#include <AP_Rally/AP_Rally.h>
class LoggerMessageWriter {
public: