mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: move logger object up to AP_Vehicle
This commit is contained in:
parent
4e97561d5b
commit
fcd7c5beb9
|
@ -483,6 +483,11 @@ const struct LogStructure Plane::log_structure[] = {
|
|||
#endif
|
||||
};
|
||||
|
||||
uint8_t Plane::get_num_log_structures() const
|
||||
{
|
||||
return ARRAY_SIZE(log_structure);
|
||||
}
|
||||
|
||||
void Plane::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
// only 200(?) bytes are guaranteed by AP_Logger
|
||||
|
@ -498,12 +503,4 @@ void Plane::Log_Write_Vehicle_Startup_Messages()
|
|||
gps.Write_AP_Logger_Log_Startup_messages();
|
||||
}
|
||||
|
||||
/*
|
||||
initialise logging subsystem
|
||||
*/
|
||||
void Plane::log_init(void)
|
||||
{
|
||||
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
}
|
||||
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
|
|
@ -908,12 +908,6 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
GOBJECT(camera_mount, "MNT", AP_Mount),
|
||||
#endif
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// @Group: LOG
|
||||
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
||||
GOBJECT(logger, "LOG", AP_Logger),
|
||||
#endif
|
||||
|
||||
// @Group: BATT
|
||||
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
|
||||
GOBJECT(battery, "BATT", AP_BattMonitor),
|
||||
|
@ -1579,5 +1573,10 @@ void Plane::load_parameters(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Feb-2024 for Copter-4.6
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, 0, true);
|
||||
#endif
|
||||
|
||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||
}
|
||||
|
|
|
@ -24,9 +24,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
|||
constructor for main Plane class
|
||||
*/
|
||||
Plane::Plane(void)
|
||||
#if HAL_LOGGING_ENABLED
|
||||
: logger(g.log_bitmask)
|
||||
#endif
|
||||
{
|
||||
// C++11 doesn't allow in-class initialisation of bitfields
|
||||
auto_state.takeoff_complete = true;
|
||||
|
|
|
@ -192,10 +192,6 @@ private:
|
|||
RC_Channel *channel_flap;
|
||||
RC_Channel *channel_airbrake;
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP_Logger logger;
|
||||
#endif
|
||||
|
||||
// scaled roll limit based on pitch
|
||||
int32_t roll_limit_cd;
|
||||
float pitch_limit_min;
|
||||
|
@ -886,9 +882,16 @@ private:
|
|||
int16_t calc_nav_yaw_course(void);
|
||||
int16_t calc_nav_yaw_ground(void);
|
||||
|
||||
// Log.cpp
|
||||
uint32_t last_log_fast_ms;
|
||||
#if HAL_LOGGING_ENABLED
|
||||
|
||||
// methods for AP_Vehicle:
|
||||
const AP_Int32 &get_log_bitmask() override { return g.log_bitmask; }
|
||||
const struct LogStructure *get_log_structures() const override {
|
||||
return log_structure;
|
||||
}
|
||||
uint8_t get_num_log_structures() const override;
|
||||
|
||||
// Log.cpp
|
||||
void Log_Write_FullRate(void);
|
||||
void Log_Write_Attitude(void);
|
||||
void Log_Write_Control_Tuning();
|
||||
|
@ -900,6 +903,7 @@ private:
|
|||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void Log_Write_AETR();
|
||||
void log_init();
|
||||
#endif
|
||||
|
||||
// Parameters.cpp
|
||||
void load_parameters(void) override;
|
||||
|
|
|
@ -64,10 +64,6 @@ void Plane::init_ardupilot()
|
|||
osd.init();
|
||||
#endif
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
log_init();
|
||||
#endif
|
||||
|
||||
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
||||
AP::compass().init();
|
||||
|
||||
|
|
Loading…
Reference in New Issue