mirror of https://github.com/ArduPilot/ardupilot
ArduSub: move logger object up to AP_Vehicle
This commit is contained in:
parent
fcd7c5beb9
commit
80fa661042
|
@ -275,6 +275,11 @@ const struct LogStructure Sub::log_structure[] = {
|
||||||
"GUIP", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
|
"GUIP", "QBffffff", "TimeUS,Type,pX,pY,pZ,vX,vY,vZ", "s-mmmnnn", "F-000000" },
|
||||||
};
|
};
|
||||||
|
|
||||||
|
uint8_t Sub::get_num_log_structures() const
|
||||||
|
{
|
||||||
|
return ARRAY_SIZE(log_structure);
|
||||||
|
}
|
||||||
|
|
||||||
void Sub::Log_Write_Vehicle_Startup_Messages()
|
void Sub::Log_Write_Vehicle_Startup_Messages()
|
||||||
{
|
{
|
||||||
// only 200(?) bytes are guaranteed by AP_Logger
|
// only 200(?) bytes are guaranteed by AP_Logger
|
||||||
|
@ -284,9 +289,4 @@ void Sub::Log_Write_Vehicle_Startup_Messages()
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void Sub::log_init()
|
|
||||||
{
|
|
||||||
logger.Init(log_structure, ARRAY_SIZE(log_structure));
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // HAL_LOGGING_ENABLED
|
#endif // HAL_LOGGING_ENABLED
|
||||||
|
|
|
@ -561,12 +561,6 @@ const AP_Param::Info Sub::var_info[] = {
|
||||||
GOBJECT(camera_mount, "MNT", AP_Mount),
|
GOBJECT(camera_mount, "MNT", AP_Mount),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
// @Group: LOG
|
|
||||||
// @Path: ../libraries/AP_Logger/AP_Logger.cpp
|
|
||||||
GOBJECT(logger, "LOG", AP_Logger),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Group: BATT
|
// @Group: BATT
|
||||||
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
|
// @Path: ../libraries/AP_BattMonitor/AP_BattMonitor.cpp
|
||||||
GOBJECT(battery, "BATT", AP_BattMonitor),
|
GOBJECT(battery, "BATT", AP_BattMonitor),
|
||||||
|
@ -814,6 +808,11 @@ void Sub::load_parameters()
|
||||||
AP_Param::convert_class(scripting_info.old_key, &scripting, scripting.var_info, scripting_old_index, scripting_old_top_element, false);
|
AP_Param::convert_class(scripting_info.old_key, &scripting, scripting.var_info, scripting_old_index, scripting_old_top_element, false);
|
||||||
}
|
}
|
||||||
#endif
|
#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
|
||||||
}
|
}
|
||||||
|
|
||||||
void Sub::convert_old_parameters()
|
void Sub::convert_old_parameters()
|
||||||
|
|
|
@ -25,9 +25,6 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL();
|
||||||
*/
|
*/
|
||||||
Sub::Sub()
|
Sub::Sub()
|
||||||
:
|
:
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
logger(g.log_bitmask),
|
|
||||||
#endif
|
|
||||||
control_mode(Mode::Number::MANUAL),
|
control_mode(Mode::Number::MANUAL),
|
||||||
motors(MAIN_LOOP_RATE),
|
motors(MAIN_LOOP_RATE),
|
||||||
auto_mode(Auto_WP),
|
auto_mode(Auto_WP),
|
||||||
|
|
|
@ -146,10 +146,6 @@ private:
|
||||||
RC_Channel *channel_forward;
|
RC_Channel *channel_forward;
|
||||||
RC_Channel *channel_lateral;
|
RC_Channel *channel_lateral;
|
||||||
|
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
AP_Logger logger;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
AP_LeakDetector leak_detector;
|
AP_LeakDetector leak_detector;
|
||||||
|
|
||||||
struct {
|
struct {
|
||||||
|
@ -403,6 +399,13 @@ private:
|
||||||
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt);
|
float get_surface_tracking_climb_rate(int16_t target_rate, float current_alt_target, float dt);
|
||||||
void rotate_body_frame_to_NE(float &x, float &y);
|
void rotate_body_frame_to_NE(float &x, float &y);
|
||||||
#if HAL_LOGGING_ENABLED
|
#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;
|
||||||
|
|
||||||
void Log_Write_Control_Tuning();
|
void Log_Write_Control_Tuning();
|
||||||
void Log_Write_Attitude();
|
void Log_Write_Attitude();
|
||||||
void Log_Write_Data(LogDataID id, int32_t value);
|
void Log_Write_Data(LogDataID id, int32_t value);
|
||||||
|
|
|
@ -52,10 +52,6 @@ void Sub::init_ardupilot()
|
||||||
// setup telem slots with serial ports
|
// setup telem slots with serial ports
|
||||||
gcs().setup_uarts();
|
gcs().setup_uarts();
|
||||||
|
|
||||||
#if HAL_LOGGING_ENABLED
|
|
||||||
log_init();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// initialise rc channels including setting mode
|
// initialise rc channels including setting mode
|
||||||
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
|
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
|
||||||
rc().init();
|
rc().init();
|
||||||
|
|
Loading…
Reference in New Issue