Blimp: move logger object up to AP_Vehicle

This commit is contained in:
Peter Barker 2024-02-07 22:27:57 +11:00 committed by Andrew Tridgell
parent 80fa661042
commit ff1ccdf2ee
5 changed files with 18 additions and 25 deletions

View File

@ -286,9 +286,6 @@ void Blimp::rotate_NE_to_BF(Vector2f &vec)
*/
Blimp::Blimp(void)
:
#if HAL_LOGGING_ENABLED
logger(g.log_bitmask),
#endif
flight_modes(&g.flight_mode1),
control_mode(Mode::Number::MANUAL),
rc_throttle_control_in_filter(1.0f),

View File

@ -113,10 +113,6 @@ private:
RC_Channel *channel_up;
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;
@ -354,8 +350,14 @@ private:
void landinggear_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_Performance();
void Log_Write_Attitude();
void Log_Write_PIDs();
void Log_Write_EKF_POS();
@ -365,11 +367,9 @@ private:
void Log_Write_Data(LogDataID id, uint16_t value);
void Log_Write_Data(LogDataID id, float value);
void Log_Write_Parameter_Tuning(uint8_t param, float tuning_val, float tune_min, float tune_max);
void Log_Write_GuidedTarget(uint8_t target_type, const Vector3f& pos_target, const Vector3f& vel_target);
void Log_Write_Vehicle_Startup_Messages();
void log_init(void);
void Write_FINI(float right, float front, float down, float yaw);
void Write_FINO(float *amp, float *off);
#endif

View File

@ -393,6 +393,12 @@ const struct LogStructure Blimp::log_structure[] = {
},
};
uint8_t Blimp::get_num_log_structures() const
{
return ARRAY_SIZE(log_structure);
}
void Blimp::Log_Write_Vehicle_Startup_Messages()
{
// only 200(?) bytes are guaranteed by AP_Logger
@ -402,9 +408,4 @@ void Blimp::Log_Write_Vehicle_Startup_Messages()
gps.Write_AP_Logger_Log_Startup_messages();
}
void Blimp::log_init(void)
{
logger.Init(log_structure, ARRAY_SIZE(log_structure));
}
#endif // HAL_LOGGING_ENABLED

View File

@ -341,12 +341,6 @@ const AP_Param::Info Blimp::var_info[] = {
// @Path: ../libraries/AP_AHRS/AP_AHRS.cpp
GOBJECT(ahrs, "AHRS_", AP_AHRS),
#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),
@ -895,6 +889,11 @@ void Blimp::load_parameters(void)
}
#endif
// PARAMETER_CONVERSION - Added: Feb-2024
#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

View File

@ -29,10 +29,6 @@ void Blimp::init_ardupilot()
// setup telem slots with serial ports
gcs().setup_uarts();
#if HAL_LOGGING_ENABLED
log_init();
#endif
init_rc_in(); // sets up rc channels from radio
// allocate the motors class