mirror of https://github.com/ArduPilot/ardupilot
Blimp: move serial_manager parameters up to base class
This commit is contained in:
parent
3085816a16
commit
4027b32b07
|
@ -62,9 +62,7 @@ const AP_Param::Info Blimp::var_info[] = {
|
|||
// @Bitmask: 0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
|
||||
GSCALAR(throttle_behavior, "PILOT_THR_BHV", 0),
|
||||
|
||||
// @Group: SERIAL
|
||||
// @Path: ../libraries/AP_SerialManager/AP_SerialManager.cpp
|
||||
GOBJECT(serial_manager, "SERIAL", AP_SerialManager),
|
||||
// SerialManager was here
|
||||
|
||||
// @Param: TELEM_DELAY
|
||||
// @DisplayName: Telemetry startup delay
|
||||
|
@ -859,6 +857,15 @@ void Blimp::load_parameters(void)
|
|||
AP_Param::convert_class(g.k_param_logger, &logger, logger.var_info, 0, true);
|
||||
#endif
|
||||
|
||||
static const AP_Param::TopLevelObjectConversion toplevel_conversions[] {
|
||||
#if AP_SERIALMANAGER_ENABLED
|
||||
// PARAMETER_CONVERSION - Added: Feb-2024
|
||||
{ &serial_manager, serial_manager.var_info, Parameters::k_param_serial_manager_old },
|
||||
#endif
|
||||
};
|
||||
|
||||
AP_Param::convert_toplevel_objects(toplevel_conversions, ARRAY_SIZE(toplevel_conversions));
|
||||
|
||||
// setup AP_Param frame type flags
|
||||
AP_Param::set_frame_type_flags(AP_PARAM_FRAME_BLIMP);
|
||||
}
|
||||
|
|
|
@ -134,7 +134,7 @@ public:
|
|||
k_param_sysid_my_gcs,
|
||||
k_param_telem_delay,
|
||||
k_param_gcs2,
|
||||
k_param_serial_manager,
|
||||
k_param_serial_manager_old,
|
||||
k_param_gcs3,
|
||||
k_param_gcs_pid_mask,
|
||||
k_param_gcs4,
|
||||
|
|
Loading…
Reference in New Issue