mirror of https://github.com/ArduPilot/ardupilot
Sub: move scripting up to AP_Vehicle
This commit is contained in:
parent
b315192dcf
commit
00bca3499f
|
@ -713,11 +713,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
||||||
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
|
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
|
||||||
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),
|
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
// 18 was scripting
|
||||||
// @Group: SCR_
|
|
||||||
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
|
|
||||||
AP_SUBGROUPINFO(scripting, "SCR_", 18, ParametersG2, AP_Scripting),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// 19 was airspeed
|
// 19 was airspeed
|
||||||
|
|
||||||
|
@ -803,6 +799,20 @@ void Sub::load_parameters()
|
||||||
const uint16_t stats_old_top_element = 4033; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
const uint16_t stats_old_top_element = 4033; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
||||||
AP_Param::convert_class(stats_info.old_key, &stats, stats.var_info, stats_old_index, stats_old_top_element, false);
|
AP_Param::convert_class(stats_info.old_key, &stats, stats.var_info, stats_old_index, stats_old_top_element, false);
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
// PARAMETER_CONVERSION - Added: Jan-2024
|
||||||
|
#if AP_SCRIPTING_ENABLED
|
||||||
|
{
|
||||||
|
// Find G2's Top Level Key
|
||||||
|
AP_Param::ConversionInfo scripting_info;
|
||||||
|
if (!AP_Param::find_top_level_key_by_pointer(&g2, scripting_info.old_key)) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const uint16_t scripting_old_index = 18; // Old parameter index in g2
|
||||||
|
const uint16_t scripting_old_top_element = 82; // Old group element in the tree for the first subgroup element (see AP_PARAM_KEY_DUMP)
|
||||||
|
AP_Param::convert_class(scripting_info.old_key, &scripting, scripting.var_info, scripting_old_index, scripting_old_top_element, false);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -7,10 +7,6 @@
|
||||||
#include <AP_Gripper/AP_Gripper.h>
|
#include <AP_Gripper/AP_Gripper.h>
|
||||||
#include <AP_Arming/AP_Arming.h>
|
#include <AP_Arming/AP_Arming.h>
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
#include <AP_Scripting/AP_Scripting.h>
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Global parameter class.
|
// Global parameter class.
|
||||||
//
|
//
|
||||||
class Parameters {
|
class Parameters {
|
||||||
|
@ -372,9 +368,6 @@ public:
|
||||||
// control over servo output ranges
|
// control over servo output ranges
|
||||||
SRV_Channels servo_channels;
|
SRV_Channels servo_channels;
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
AP_Scripting scripting;
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
|
||||||
};
|
};
|
||||||
|
|
||||||
extern const AP_Param::Info var_info[];
|
extern const AP_Param::Info var_info[];
|
||||||
|
|
|
@ -157,10 +157,6 @@ void Sub::init_ardupilot()
|
||||||
|
|
||||||
startup_INS_ground();
|
startup_INS_ground();
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
|
||||||
g2.scripting.init();
|
|
||||||
#endif // AP_SCRIPTING_ENABLED
|
|
||||||
|
|
||||||
// enable CPU failsafe
|
// enable CPU failsafe
|
||||||
mainloop_failsafe_enable();
|
mainloop_failsafe_enable();
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue