mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane: move scripting up to AP_Vehicle
This commit is contained in:
parent
7a14427d26
commit
33895e8816
@ -1100,11 +1100,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
// @User: Advanced
|
// @User: Advanced
|
||||||
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
// 14 was AP_Scripting
|
||||||
// @Group: SCR_
|
|
||||||
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
|
|
||||||
AP_SUBGROUPINFO(scripting, "SCR_", 14, ParametersG2, AP_Scripting),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// @Param: TKOFF_ACCEL_CNT
|
// @Param: TKOFF_ACCEL_CNT
|
||||||
// @DisplayName: Takeoff throttle acceleration count
|
// @DisplayName: Takeoff throttle acceleration count
|
||||||
@ -1568,6 +1564,20 @@ void Plane::load_parameters(void)
|
|||||||
AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false);
|
AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
// PARAMETER_CONVERSION - Added: Jan-2024 for Plane-4.6
|
||||||
|
#if AP_SCRIPTING_ENABLED
|
||||||
|
{
|
||||||
|
// Find G2's Top Level Key
|
||||||
|
AP_Param::ConversionInfo info;
|
||||||
|
if (!AP_Param::find_top_level_key_by_pointer(&g2, info.old_key)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const uint16_t old_index = 14; // Old parameter index in g2
|
||||||
|
const uint16_t old_top_element = 78; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
||||||
|
AP_Param::convert_class(info.old_key, &scripting, scripting.var_info, old_index, old_top_element, false);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
hal.console->printf("load_all took %uus\n", (unsigned)(micros() - before));
|
||||||
}
|
}
|
||||||
|
@ -519,10 +519,6 @@ public:
|
|||||||
|
|
||||||
AP_Int32 flight_options;
|
AP_Int32 flight_options;
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
AP_Scripting scripting;
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
|
||||||
|
|
||||||
AP_Int8 takeoff_throttle_accel_count;
|
AP_Int8 takeoff_throttle_accel_count;
|
||||||
AP_Int8 takeoff_timeout;
|
AP_Int8 takeoff_timeout;
|
||||||
|
|
||||||
|
@ -176,10 +176,6 @@ void Plane::startup_ground(void)
|
|||||||
);
|
);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
g2.scripting.init();
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
|
||||||
|
|
||||||
// reset last heartbeat time, so we don't trigger failsafe on slow
|
// reset last heartbeat time, so we don't trigger failsafe on slow
|
||||||
// startup
|
// startup
|
||||||
gcs().sysid_myggcs_seen(AP_HAL::millis());
|
gcs().sysid_myggcs_seen(AP_HAL::millis());
|
||||||
|
Loading…
Reference in New Issue
Block a user