Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Move AP_Scripting object up to AP_Vehicle #26097

Merged
merged 12 commits into from
Feb 7, 2024
Merged
11 changes: 5 additions & 6 deletions AntennaTracker/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -505,12 +505,6 @@ const AP_Param::Info Tracker::var_info[] = {

GGROUP(pidYaw2Srv, "YAW2SRV_", AC_PID),

#if AP_SCRIPTING_ENABLED
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
GOBJECT(scripting, "SCR_", AP_Scripting),
#endif

// @Param: CMD_TOTAL
// @DisplayName: Number of loaded mission items
// @Description: Set to 1 if HOME location has been loaded by the ground station. Do not change this manually.
Expand Down Expand Up @@ -619,6 +613,11 @@ void Tracker::load_parameters(void)
AP_Param::convert_class(g.k_param_stats_old, &stats, stats.var_info, 0, 0, true);
#endif

#if AP_SCRIPTING_ENABLED
// PARAMETER_CONVERSION - Added: Jan-2024
AP_Param::convert_class(g.k_param_scripting_old, &scripting, scripting.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
Expand Down
2 changes: 1 addition & 1 deletion AntennaTracker/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ class Parameters {
k_param_servo_channels,

k_param_stats_old = 218,
k_param_scripting = 219,
k_param_scripting_old = 219,

//
// 220: Waypoint data
Expand Down
8 changes: 0 additions & 8 deletions AntennaTracker/Tracker.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,10 +53,6 @@

#include "AP_Arming.h"

#if AP_SCRIPTING_ENABLED
#include <AP_Scripting/AP_Scripting.h>
#endif

#include "mode.h"

class Tracker : public AP_Vehicle {
Expand Down Expand Up @@ -115,10 +111,6 @@ class Tracker : public AP_Vehicle {
ModeServoTest mode_servotest;
ModeStop mode_stop;

#if AP_SCRIPTING_ENABLED
AP_Scripting scripting;
#endif

// Vehicle state
struct {
bool location_valid; // true if we have a valid location for the vehicle
Expand Down
4 changes: 0 additions & 4 deletions AntennaTracker/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,6 @@ void Tracker::init_ardupilot()
log_init();
#endif

#if AP_SCRIPTING_ENABLED
scripting.init();
#endif // AP_SCRIPTING_ENABLED

// initialise compass
AP::compass().set_log_bit(MASK_LOG_COMPASS);
AP::compass().init();
Expand Down
22 changes: 17 additions & 5 deletions ArduCopter/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -821,6 +821,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0),

// 12 was AP_Stats

#if AP_GRIPPER_ENABLED
// @Group: GRIP_
// @Path: ../libraries/AP_Gripper/AP_Gripper.cpp
Expand Down Expand Up @@ -911,11 +913,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPPTR(autotune_ptr, "AUTOTUNE_", 29, ParametersG2, AutoTune),
#endif

#if AP_SCRIPTING_ENABLED
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO(scripting, "SCR_", 30, ParametersG2, AP_Scripting),
#endif
// 30 was AP_Scripting

// @Param: TUNE_MIN
// @DisplayName: Tuning minimum
Expand Down Expand Up @@ -1390,6 +1388,20 @@ void Copter::load_parameters(void)
AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false);
}
#endif
// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-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 = 30; // Old parameter index in g2
const uint16_t old_top_element = 94; // 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));

Expand Down
4 changes: 0 additions & 4 deletions ArduCopter/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -600,10 +600,6 @@ class ParametersG2 {
void *autotune_ptr;
#endif

#if AP_SCRIPTING_ENABLED
AP_Scripting scripting;
#endif // AP_SCRIPTING_ENABLED

AP_Float tuning_min;
AP_Float tuning_max;

Expand Down
4 changes: 0 additions & 4 deletions ArduCopter/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -179,10 +179,6 @@ void Copter::init_ardupilot()

startup_INS_ground();

#if AP_SCRIPTING_ENABLED
g2.scripting.init();
#endif // AP_SCRIPTING_ENABLED

#if AC_CUSTOMCONTROL_MULTI_ENABLED == ENABLED
custom_control.init();
#endif
Expand Down
22 changes: 17 additions & 5 deletions ArduPlane/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1033,6 +1033,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("SYSID_ENFORCE", 4, ParametersG2, sysid_enforce, 0),

// AP_Stats was 5

// @Group: SERVO
// @Path: ../libraries/SRV_Channel/SRV_Channels.cpp
AP_SUBGROUPINFO(servo_channels, "SERVO", 6, ParametersG2, SRV_Channels),
Expand Down Expand Up @@ -1098,11 +1100,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("FLIGHT_OPTIONS", 13, ParametersG2, flight_options, 0),

#if AP_SCRIPTING_ENABLED
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO(scripting, "SCR_", 14, ParametersG2, AP_Scripting),
#endif
// 14 was AP_Scripting

// @Param: TKOFF_ACCEL_CNT
// @DisplayName: Takeoff throttle acceleration count
Expand Down Expand Up @@ -1566,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);
}
#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));
}
4 changes: 0 additions & 4 deletions ArduPlane/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -519,10 +519,6 @@ class ParametersG2 {

AP_Int32 flight_options;

#if AP_SCRIPTING_ENABLED
AP_Scripting scripting;
#endif // AP_SCRIPTING_ENABLED

AP_Int8 takeoff_throttle_accel_count;
AP_Int8 takeoff_timeout;

Expand Down
4 changes: 0 additions & 4 deletions ArduPlane/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,10 +176,6 @@ void Plane::startup_ground(void)
);
#endif

#if AP_SCRIPTING_ENABLED
g2.scripting.init();
#endif // AP_SCRIPTING_ENABLED

// reset last heartbeat time, so we don't trigger failsafe on slow
// startup
gcs().sysid_myggcs_seen(AP_HAL::millis());
Expand Down
23 changes: 18 additions & 5 deletions ArduSub/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -690,6 +690,9 @@ const AP_Param::Info Sub::var_info[] = {
2nd group of parameters
*/
const AP_Param::GroupInfo ParametersG2::var_info[] = {

// 1 was AP_Stats

#if HAL_PROXIMITY_ENABLED
// @Group: PRX
// @Path: ../libraries/AP_Proximity/AP_Proximity.cpp
Expand All @@ -710,11 +713,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @Path: ../libraries/RC_Channel/RC_Channels_VarInfo.h
AP_SUBGROUPINFO(rc_channels, "RC", 17, ParametersG2, RC_Channels),

#if AP_SCRIPTING_ENABLED
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO(scripting, "SCR_", 18, ParametersG2, AP_Scripting),
#endif
// 18 was scripting

// 19 was airspeed

Expand Down Expand Up @@ -800,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)
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
}

Expand Down
7 changes: 0 additions & 7 deletions ArduSub/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -7,10 +7,6 @@
#include <AP_Gripper/AP_Gripper.h>
#include <AP_Arming/AP_Arming.h>

#if AP_SCRIPTING_ENABLED
#include <AP_Scripting/AP_Scripting.h>
#endif

// Global parameter class.
//
class Parameters {
Expand Down Expand Up @@ -372,9 +368,6 @@ class ParametersG2 {
// control over servo output ranges
SRV_Channels servo_channels;

#if AP_SCRIPTING_ENABLED
AP_Scripting scripting;
#endif // AP_SCRIPTING_ENABLED
};

extern const AP_Param::Info var_info[];
Expand Down
4 changes: 0 additions & 4 deletions ArduSub/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -157,10 +157,6 @@ void Sub::init_ardupilot()

startup_INS_ground();

#if AP_SCRIPTING_ENABLED
g2.scripting.init();
#endif // AP_SCRIPTING_ENABLED

// enable CPU failsafe
mainloop_failsafe_enable();

Expand Down
22 changes: 17 additions & 5 deletions Blimp/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -780,6 +780,8 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Advanced
AP_GROUPINFO("SYSID_ENFORCE", 11, ParametersG2, sysid_enforce, 0),

// 12 was AP_Stats

// @Param: FRAME_CLASS
// @DisplayName: Frame Class
// @Description: Controls major frame class for blimp.
Expand All @@ -805,11 +807,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard
AP_GROUPINFO("PILOT_SPEED_DN", 24, ParametersG2, pilot_speed_dn, 0),

#if AP_SCRIPTING_ENABLED
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO(scripting, "SCR_", 30, ParametersG2, AP_Scripting),
#endif
// 30 was AP_Scripting

// @Param: FS_VIBE_ENABLE
// @DisplayName: Vibration Failsafe enable
Expand Down Expand Up @@ -882,6 +880,20 @@ void Blimp::load_parameters(void)
AP_Param::convert_class(info.old_key, &stats, stats.var_info, old_index, old_top_element, false);
}
#endif
// PARAMETER_CONVERSION - Added: Jan-2024 for Copter-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 = 30; // Old parameter index in g2
const uint16_t old_top_element = 94; // 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));

Expand Down
5 changes: 0 additions & 5 deletions Blimp/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -305,11 +305,6 @@ class ParametersG2
// Land alt final stage
AP_Int16 land_alt_low;


#if AP_SCRIPTING_ENABLED
AP_Scripting scripting;
#endif // AP_SCRIPTING_ENABLED

// vibration failsafe enable/disable
AP_Int8 fs_vibe_enabled;

Expand Down
4 changes: 0 additions & 4 deletions Blimp/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,10 +79,6 @@ void Blimp::init_ardupilot()

startup_INS_ground();

#if AP_SCRIPTING_ENABLED
g2.scripting.init();
#endif // AP_SCRIPTING_ENABLED

ins.set_log_raw_bit(MASK_LOG_IMU_RAW);

// setup fin output
Expand Down
22 changes: 17 additions & 5 deletions Rover/Parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -404,6 +404,8 @@ const AP_Param::Info Rover::var_info[] = {
2nd group of parameters
*/
const AP_Param::GroupInfo ParametersG2::var_info[] = {
// 1 was AP_Stats

// @Param: SYSID_ENFORCE
// @DisplayName: GCS sysid enforcement
// @Description: This controls whether packets from other than the expected GCS system ID will be accepted
Expand Down Expand Up @@ -599,11 +601,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
// @User: Standard
AP_GROUPINFO("BAL_PITCH_TRIM", 40, ParametersG2, bal_pitch_trim, 0),

#if AP_SCRIPTING_ENABLED
// @Group: SCR_
// @Path: ../libraries/AP_Scripting/AP_Scripting.cpp
AP_SUBGROUPINFO(scripting, "SCR_", 41, ParametersG2, AP_Scripting),
#endif
// 41 was Scripting

// @Param: STICK_MIXING
// @DisplayName: Stick Mixing
Expand Down Expand Up @@ -931,5 +929,19 @@ void Rover::load_parameters(void)
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 for Rover-4.6
#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 = 41; // Old parameter index in g2
const uint16_t scripting_old_top_element = 105; // 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

}
4 changes: 0 additions & 4 deletions Rover/Parameters.h
Original file line number Diff line number Diff line change
Expand Up @@ -396,10 +396,6 @@ class ParametersG2 {
// stick mixing for auto modes
AP_Int8 stick_mixing;

#if AP_SCRIPTING_ENABLED
AP_Scripting scripting;
#endif // AP_SCRIPTING_ENABLED

// waypoint navigation
AR_WPNav_OA wp_nav;

Expand Down
Loading
Loading