mirror of https://github.com/ArduPilot/ardupilot
Tools: move logger object up to AP_Vehicle
This commit is contained in:
parent
7b3a91996b
commit
bdb84181bc
|
@ -62,9 +62,6 @@ void loop(void)
|
|||
static uint32_t start_ms;
|
||||
|
||||
AP_Periph_FW::AP_Periph_FW()
|
||||
#if HAL_LOGGING_ENABLED
|
||||
: logger(g.log_bitmask)
|
||||
#endif
|
||||
{
|
||||
if (_singleton != nullptr) {
|
||||
AP_HAL::panic("AP_Periph_FW must be singleton");
|
||||
|
@ -127,7 +124,7 @@ void AP_Periph_FW::init()
|
|||
#endif
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
logger.init(g.log_bitmask, log_structure, ARRAY_SIZE(log_structure));
|
||||
#endif
|
||||
|
||||
check_firmware_print();
|
||||
|
|
|
@ -69,10 +69,6 @@ const AP_Param::Info ReplayVehicle::var_info[] = {
|
|||
// @Path: ../libraries/AP_Compass/AP_Compass.cpp
|
||||
GOBJECT(compass, "COMPASS_", Compass),
|
||||
|
||||
// @Group: LOG
|
||||
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
||||
GOBJECT(logger, "LOG", AP_Logger),
|
||||
|
||||
// @Group: EK3_
|
||||
// @Path: ../libraries/AP_NavEKF3/AP_NavEKF3.cpp
|
||||
GOBJECTN(ekf3, NavEKF3, "EK3_", NavEKF3),
|
||||
|
@ -124,7 +120,6 @@ void ReplayVehicle::init_ardupilot(void)
|
|||
// message as a product of Replay), or the format understood in
|
||||
// the current code (if we do emit the message in the normal
|
||||
// places in the EKF, for example)
|
||||
logger.Init(log_structure, 0);
|
||||
logger.set_force_log_disarmed(true);
|
||||
}
|
||||
|
||||
|
|
|
@ -34,7 +34,7 @@ class ReplayVehicle : public AP_Vehicle {
|
|||
public:
|
||||
friend class Replay;
|
||||
|
||||
ReplayVehicle() { unused.set(-1); }
|
||||
ReplayVehicle() { unused_log_bitmask.set(-1); }
|
||||
// HAL::Callbacks implementation.
|
||||
void load_parameters(void) override;
|
||||
void get_scheduler_tasks(const AP_Scheduler::Task *&tasks,
|
||||
|
@ -50,16 +50,25 @@ public:
|
|||
|
||||
AP_FixedWing aparm;
|
||||
|
||||
AP_Int32 unused; // logging is magic for Replay; this is unused
|
||||
AP_Int32 unused_log_bitmask; // logging is magic for Replay; this is unused
|
||||
struct LogStructure log_structure[256] = {
|
||||
};
|
||||
AP_Logger logger{unused};
|
||||
|
||||
NavEKF2 ekf2;
|
||||
NavEKF3 ekf3;
|
||||
|
||||
protected:
|
||||
|
||||
protected:
|
||||
|
||||
const AP_Int32 &get_log_bitmask() override { return unused_log_bitmask; }
|
||||
const struct LogStructure *get_log_structures() const override {
|
||||
return log_structure;
|
||||
}
|
||||
uint8_t get_num_log_structures() const override {
|
||||
return uint8_t(ARRAY_SIZE(log_structure));
|
||||
}
|
||||
|
||||
void init_ardupilot() override;
|
||||
|
||||
private:
|
||||
|
@ -82,7 +91,7 @@ public:
|
|||
|
||||
// return true if a user parameter of name is set
|
||||
bool check_user_param(const char *name);
|
||||
|
||||
|
||||
private:
|
||||
const char *filename;
|
||||
ReplayVehicle &_vehicle;
|
||||
|
|
Loading…
Reference in New Issue