diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 5374c79357..dda496b3e0 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -820,9 +820,6 @@ bool Copter::get_rate_ef_targets(Vector3f& rate_ef_targets) const */ Copter::Copter(void) : -#if HAL_LOGGING_ENABLED - logger(g.log_bitmask), -#endif flight_modes(&g.flight_mode1), simple_cos_yaw(1.0f), super_simple_cos_yaw(1.0), diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 53576d969b..3c922cb140 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -251,10 +251,6 @@ private: RC_Channel *channel_throttle; RC_Channel *channel_yaw; -#if HAL_LOGGING_ENABLED - AP_Logger logger; -#endif - // flight modes convenience array AP_Int8 *flight_modes; const uint8_t num_flight_modes = 6; @@ -846,6 +842,13 @@ private: void standby_update(); #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_Control_Tuning(); void Log_Write_Attitude(); @@ -866,7 +869,6 @@ private: void Log_Write_SysID_Setup(uint8_t systemID_axis, float waveform_magnitude, float frequency_start, float frequency_stop, float time_fade_in, float time_const_freq, float time_record, float time_fade_out); void Log_Write_SysID_Data(float waveform_time, float waveform_sample, float waveform_freq, float angle_x, float angle_y, float angle_z, float accel_x, float accel_y, float accel_z); void Log_Write_Vehicle_Startup_Messages(); - void log_init(void); #endif // HAL_LOGGING_ENABLED // mode.cpp diff --git a/ArduCopter/Log.cpp b/ArduCopter/Log.cpp index 4d9e4ef87b..d1d530ca13 100644 --- a/ArduCopter/Log.cpp +++ b/ArduCopter/Log.cpp @@ -560,6 +560,11 @@ const struct LogStructure Copter::log_structure[] = { "GUIA", "QBffffffff", "TimeUS,Type,Roll,Pitch,Yaw,RollRt,PitchRt,YawRt,Thrust,ClimbRt", "s-dddkkk-n", "F-000000-0" , true }, }; +uint8_t Copter::get_num_log_structures() const +{ + return ARRAY_SIZE(log_structure); +} + void Copter::Log_Write_Vehicle_Startup_Messages() { // only 200(?) bytes are guaranteed by AP_Logger @@ -571,9 +576,4 @@ void Copter::Log_Write_Vehicle_Startup_Messages() gps.Write_AP_Logger_Log_Startup_messages(); } -void Copter::log_init(void) -{ - logger.Init(log_structure, ARRAY_SIZE(log_structure)); -} - #endif // HAL_LOGGING_ENABLED diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 35b1780ff9..d5d7174ff1 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -554,12 +554,6 @@ const AP_Param::Info Copter::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), @@ -1410,6 +1404,11 @@ void Copter::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)); // setup AP_Param frame type flags diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 31b9662824..5347a67901 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -44,10 +44,6 @@ void Copter::init_ardupilot() osd.init(); #endif -#if HAL_LOGGING_ENABLED - log_init(); -#endif - // update motor interlock state update_using_interlock();