mirror of https://github.com/ArduPilot/ardupilot
AP_Logger: move logger object up to AP_Vehicle
This commit is contained in:
parent
dc74f97739
commit
e39fad1411
|
@ -193,8 +193,7 @@ const AP_Param::GroupInfo AP_Logger::var_info[] = {
|
|||
|
||||
#define streq(x, y) (!strcmp(x, y))
|
||||
|
||||
AP_Logger::AP_Logger(const AP_Int32 &log_bitmask)
|
||||
: _log_bitmask(log_bitmask)
|
||||
AP_Logger::AP_Logger()
|
||||
{
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
if (_singleton != nullptr) {
|
||||
|
@ -204,8 +203,10 @@ AP_Logger::AP_Logger(const AP_Int32 &log_bitmask)
|
|||
_singleton = this;
|
||||
}
|
||||
|
||||
void AP_Logger::Init(const struct LogStructure *structures, uint8_t num_types)
|
||||
void AP_Logger::init(const AP_Int32 &log_bitmask, const struct LogStructure *structures, uint8_t num_types)
|
||||
{
|
||||
_log_bitmask = &log_bitmask;
|
||||
|
||||
// convert from 8 bit to 16 bit LOG_FILE_BUFSIZE
|
||||
_params.file_bufsize.convert_parameter_width(AP_PARAM_INT8);
|
||||
|
||||
|
@ -629,7 +630,7 @@ bool AP_Logger::should_log(const uint32_t mask) const
|
|||
{
|
||||
bool armed = vehicle_is_armed();
|
||||
|
||||
if (!(mask & _log_bitmask)) {
|
||||
if (!(mask & *_log_bitmask)) {
|
||||
return false;
|
||||
}
|
||||
if (!armed && !log_while_disarmed()) {
|
||||
|
|
|
@ -187,7 +187,7 @@ class AP_Logger
|
|||
public:
|
||||
FUNCTOR_TYPEDEF(vehicle_startup_message_Writer, void);
|
||||
|
||||
AP_Logger(const AP_Int32 &log_bitmask);
|
||||
AP_Logger();
|
||||
|
||||
/* Do not allow copies */
|
||||
CLASS_NO_COPY(AP_Logger);
|
||||
|
@ -198,7 +198,7 @@ public:
|
|||
}
|
||||
|
||||
// initialisation
|
||||
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||
void init(const AP_Int32 &log_bitmask, const struct LogStructure *structure, uint8_t num_types);
|
||||
void set_num_types(uint8_t num_types) { _num_types = num_types; }
|
||||
|
||||
bool CardInserted(void);
|
||||
|
@ -426,7 +426,7 @@ private:
|
|||
#define LOGGER_MAX_BACKENDS 2
|
||||
uint8_t _next_backend;
|
||||
AP_Logger_Backend *backends[LOGGER_MAX_BACKENDS];
|
||||
const AP_Int32 &_log_bitmask;
|
||||
const AP_Int32 *_log_bitmask;
|
||||
|
||||
enum class Backend_Type : uint8_t {
|
||||
NONE = 0,
|
||||
|
|
|
@ -106,7 +106,7 @@ public:
|
|||
private:
|
||||
|
||||
AP_Int32 log_bitmask;
|
||||
AP_Logger logger{log_bitmask};
|
||||
AP_Logger logger;
|
||||
AP_Scheduler scheduler;
|
||||
|
||||
void Log_Write_TypeMessages();
|
||||
|
@ -248,7 +248,7 @@ void AP_LoggerTest_AllTypes::setup(void)
|
|||
hal.console->printf("Logger All Types 1.0\n");
|
||||
|
||||
log_bitmask.set((uint32_t)-1);
|
||||
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
logger.init(log_bitmask, log_structure, ARRAY_SIZE(log_structure));
|
||||
logger.set_vehicle_armed(true);
|
||||
logger.Write_Message("AP_Logger Test");
|
||||
|
||||
|
|
|
@ -41,7 +41,7 @@ public:
|
|||
private:
|
||||
|
||||
AP_Int32 log_bitmask;
|
||||
AP_Logger logger{log_bitmask};
|
||||
AP_Logger logger;
|
||||
AP_Scheduler scheduler;
|
||||
|
||||
};
|
||||
|
@ -53,7 +53,7 @@ void AP_LoggerTest::setup(void)
|
|||
hal.console->printf("Logger Log Test 1.0\n");
|
||||
|
||||
log_bitmask.set((uint32_t)-1);
|
||||
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
logger.init(log_bitmask, log_structure, ARRAY_SIZE(log_structure));
|
||||
logger.set_vehicle_armed(true);
|
||||
logger.Write_Message("AP_Logger Test");
|
||||
#ifdef DEBUG_RATES
|
||||
|
|
Loading…
Reference in New Issue