mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: stop libraries including AP_Logger.h in .h files
AP_Logger.h is a nexus of includes; while this is being improved over time, there's no reason for the library headers to include AP_Logger.h as the logger itself is access by singleton and the structures are in LogStructure.h This necessitated moving The PID_Info structure out of AP_Logger's namespace. This cleans up a pretty nasty bit - that structure is definitely not simply used for logging, but also used to pass pid information around to controllers! There are a lot of patches in here because AP_Logger.h, acting as a nexus, was providing transitive header file inclusion in many (some unlikely!) places.
This commit is contained in:
parent
8ec0eed749
commit
0c32eeca2e
|
@ -48,6 +48,7 @@
|
|||
#define HAL_LOGGER_FILE_CONTENTS_ENABLED HAL_LOGGING_FILESYSTEM_ENABLED
|
||||
#endif
|
||||
|
||||
#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>
|
||||
|
@ -326,21 +327,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);
|
||||
|
||||
// This structure provides information on the internal member data of a PID for logging purposes
|
||||
struct PID_Info {
|
||||
float target;
|
||||
float actual;
|
||||
float error;
|
||||
float P;
|
||||
float I;
|
||||
float D;
|
||||
float FF;
|
||||
float Dmod;
|
||||
float slew_rate;
|
||||
bool limit;
|
||||
};
|
||||
|
||||
void Write_PID(uint8_t msg_type, const PID_Info &info);
|
||||
void Write_PID(uint8_t msg_type, const AP_PIDInfo &info);
|
||||
|
||||
// returns true if logging of a message should be attempted
|
||||
bool should_log(uint32_t mask) const;
|
||||
|
|
|
@ -407,7 +407,7 @@ void AP_Logger::Write_ServoStatus(uint64_t time_us, uint8_t id, float position,
|
|||
|
||||
|
||||
// Write a Yaw PID packet
|
||||
void AP_Logger::Write_PID(uint8_t msg_type, const PID_Info &info)
|
||||
void AP_Logger::Write_PID(uint8_t msg_type, const AP_PIDInfo &info)
|
||||
{
|
||||
const struct log_PID pkt{
|
||||
LOG_PACKET_HEADER_INIT(msg_type),
|
||||
|
|
Loading…
Reference in New Issue