mirror of https://github.com/ArduPilot/ardupilot
AntennaTracker: move logger object up to AP_Vehicle
This commit is contained in:
parent
ff1ccdf2ee
commit
74f2c5a881
|
@ -87,15 +87,15 @@ const struct LogStructure Tracker::log_structure[] = {
|
|||
"VPOS", "QLLefff", "TimeUS,Lat,Lng,Alt,VelX,VelY,VelZ", "sddmnnn", "FGGB000", true }
|
||||
};
|
||||
|
||||
uint8_t Tracker::get_num_log_structures() const
|
||||
{
|
||||
return ARRAY_SIZE(log_structure);
|
||||
}
|
||||
|
||||
void Tracker::Log_Write_Vehicle_Startup_Messages()
|
||||
{
|
||||
logger.Write_Mode((uint8_t)mode->number(), ModeReason::INITIALISED);
|
||||
gps.Write_AP_Logger_Log_Startup_messages();
|
||||
}
|
||||
|
||||
void Tracker::log_init(void)
|
||||
{
|
||||
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
||||
}
|
||||
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
|
|
@ -566,12 +566,6 @@ const AP_Param::Info Tracker::var_info[] = {
|
|||
// @Path: ../libraries/AP_Vehicle/AP_Vehicle.cpp
|
||||
PARAM_VEHICLE_INFO,
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
// @Group: LOG
|
||||
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
||||
GOBJECT(logger, "LOG", AP_Logger),
|
||||
#endif
|
||||
|
||||
#if HAL_NAVEKF2_AVAILABLE
|
||||
// @Group: EK2_
|
||||
// @Path: ../libraries/AP_NavEKF2/AP_NavEKF2.cpp
|
||||
|
@ -618,6 +612,11 @@ void Tracker::load_parameters(void)
|
|||
AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.var_info, 0, 0, true);
|
||||
#endif
|
||||
|
||||
// PARAMETER_CONVERSION - Added: Feb-2024 for Tracker-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 %luus\n", (unsigned long)(AP_HAL::micros() - before));
|
||||
|
||||
#if HAL_HAVE_SAFETY_SWITCH
|
||||
|
|
|
@ -164,13 +164,6 @@ void Tracker::stats_update(void)
|
|||
|
||||
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||
|
||||
Tracker::Tracker(void)
|
||||
#if HAL_LOGGING_ENABLED
|
||||
: logger(g.log_bitmask)
|
||||
#endif
|
||||
{
|
||||
}
|
||||
|
||||
Tracker tracker;
|
||||
AP_Vehicle& vehicle = tracker;
|
||||
|
||||
|
|
|
@ -64,8 +64,6 @@ public:
|
|||
friend class ModeGuided;
|
||||
friend class Mode;
|
||||
|
||||
Tracker(void);
|
||||
|
||||
void arm_servos();
|
||||
void disarm_servos();
|
||||
|
||||
|
@ -74,10 +72,6 @@ private:
|
|||
|
||||
uint32_t start_time_ms = 0;
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
AP_Logger logger;
|
||||
#endif
|
||||
|
||||
/**
|
||||
antenna control channels
|
||||
*/
|
||||
|
@ -160,12 +154,20 @@ private:
|
|||
// GCS_Mavlink.cpp
|
||||
void send_nav_controller_output(mavlink_channel_t chan);
|
||||
|
||||
#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_Attitude();
|
||||
void Log_Write_Vehicle_Baro(float pressure, float altitude);
|
||||
void Log_Write_Vehicle_Pos(int32_t lat,int32_t lng,int32_t alt, const Vector3f& vel);
|
||||
void Log_Write_Vehicle_Startup_Messages();
|
||||
void log_init(void);
|
||||
#endif
|
||||
|
||||
// Parameters.cpp
|
||||
void load_parameters(void) override;
|
||||
|
|
|
@ -24,10 +24,6 @@ void Tracker::init_ardupilot()
|
|||
// try to initialise stream rates in the main loop.
|
||||
gcs().update_send();
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
log_init();
|
||||
#endif
|
||||
|
||||
// initialise compass
|
||||
AP::compass().set_log_bit(MASK_LOG_COMPASS);
|
||||
AP::compass().init();
|
||||
|
|
Loading…
Reference in New Issue