diff --git a/.vscode/settings.default.json b/.vscode/settings.default.json index d6469cb6b6bae8..1a5ba955dd21ab 100644 --- a/.vscode/settings.default.json +++ b/.vscode/settings.default.json @@ -1,4 +1,5 @@ { "cSpell.language": "en-GB", - "astyle.astylerc": "${workspaceFolder}/Tools/CodeStyle/astylerc" + "astyle.astylerc": "${workspaceFolder}/Tools/CodeStyle/astylerc", + "Lua.runtime.version": "Lua 5.3" } diff --git a/AntennaTracker/Parameters.cpp b/AntennaTracker/Parameters.cpp index 20d8da47aa06e9..c21d5dbf4f5d7e 100644 --- a/AntennaTracker/Parameters.cpp +++ b/AntennaTracker/Parameters.cpp @@ -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. @@ -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 diff --git a/AntennaTracker/Parameters.h b/AntennaTracker/Parameters.h index 836a70853615e1..1db980b04aaa00 100644 --- a/AntennaTracker/Parameters.h +++ b/AntennaTracker/Parameters.h @@ -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 diff --git a/AntennaTracker/Tracker.h b/AntennaTracker/Tracker.h index 54b2719433fcd2..22c7687ef73ea9 100644 --- a/AntennaTracker/Tracker.h +++ b/AntennaTracker/Tracker.h @@ -53,10 +53,6 @@ #include "AP_Arming.h" -#if AP_SCRIPTING_ENABLED -#include -#endif - #include "mode.h" class Tracker : public AP_Vehicle { @@ -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 diff --git a/AntennaTracker/system.cpp b/AntennaTracker/system.cpp index a05be96b61dd24..db4438ded4c063 100644 --- a/AntennaTracker/system.cpp +++ b/AntennaTracker/system.cpp @@ -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(); diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index e8c2d5039661a3..4318da61e084e4 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -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 @@ -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 @@ -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)); diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 5ac04f8946c608..c797f86cfe1aaf 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -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; diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index ec167d96480adc..01d9d6d0ed1f02 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -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 diff --git a/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 1e6b5901bc8608..639aa73039e6a2 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -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), @@ -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 @@ -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)); } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 4a80e21943962d..ad78f76de7e216 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -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; diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 4b46bd837dd58a..56998c367904db 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -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()); diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index 90d493659b4fc3..168990b01f4c82 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -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 @@ -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 @@ -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 } diff --git a/ArduSub/Parameters.h b/ArduSub/Parameters.h index 1e0b86a4e52409..f8fd851fbf5e11 100644 --- a/ArduSub/Parameters.h +++ b/ArduSub/Parameters.h @@ -7,10 +7,6 @@ #include #include -#if AP_SCRIPTING_ENABLED -#include -#endif - // Global parameter class. // class Parameters { @@ -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[]; diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index c3653f077cc2fe..f86637c5a143ab 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -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(); diff --git a/Blimp/Parameters.cpp b/Blimp/Parameters.cpp index 592087be62ef25..f0641e0cf28229 100644 --- a/Blimp/Parameters.cpp +++ b/Blimp/Parameters.cpp @@ -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. @@ -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 @@ -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)); diff --git a/Blimp/Parameters.h b/Blimp/Parameters.h index 3d44b579a28101..769e9d2df7a4ad 100644 --- a/Blimp/Parameters.h +++ b/Blimp/Parameters.h @@ -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; diff --git a/Blimp/system.cpp b/Blimp/system.cpp index dc3799a74a410d..5bde10d45bb60f 100644 --- a/Blimp/system.cpp +++ b/Blimp/system.cpp @@ -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 diff --git a/Rover/Parameters.cpp b/Rover/Parameters.cpp index 66149625735829..1c7ae1a07b2a65 100644 --- a/Rover/Parameters.cpp +++ b/Rover/Parameters.cpp @@ -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 @@ -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 @@ -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 } diff --git a/Rover/Parameters.h b/Rover/Parameters.h index e8dbb86a0eb249..ef8d6194706ac3 100644 --- a/Rover/Parameters.h +++ b/Rover/Parameters.h @@ -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; diff --git a/Rover/system.cpp b/Rover/system.cpp index f358aee5b76486..67f0a8ebdfcbb3 100644 --- a/Rover/system.cpp +++ b/Rover/system.cpp @@ -174,10 +174,6 @@ void Rover::startup_ground(void) FUNCTOR_BIND(&rover, &Rover::Log_Write_Vehicle_Startup_Messages, void) ); #endif - -#if AP_SCRIPTING_ENABLED - g2.scripting.init(); -#endif // AP_SCRIPTING_ENABLED } // update the ahrs flyforward setting which can allow diff --git a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat index 4994a739fb77af..965cd4462cba1e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat +++ b/libraries/AP_HAL_ChibiOS/hwdef/CubePilot-CANMod/hwdef.dat @@ -85,11 +85,13 @@ define HAL_DISABLE_LOOP_DELAY ################################# define HAL_BARO_ALLOW_INIT_NO_BARO -define AP_RC_CHANNEL_ENABLED 1 define AP_INERTIALSENSOR_ENABLED 0 define AP_NETWORKING_MAX_INSTANCES 4 +define AP_SCRIPTING_ENABLED 1 +define AP_FILESYSTEM_ROMFS_ENABLED 1 + # listen for reboot command from uploader.py script # undefine to disable. Use -1 to allow on all ports, otherwise serial number index defined in SERIAL_ORDER starting at 0 define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 diff --git a/libraries/AP_Parachute/AP_Parachute.cpp b/libraries/AP_Parachute/AP_Parachute.cpp index aae6ea9bc9b942..c570f8bf6cfa85 100644 --- a/libraries/AP_Parachute/AP_Parachute.cpp +++ b/libraries/AP_Parachute/AP_Parachute.cpp @@ -241,7 +241,17 @@ bool AP_Parachute::arming_checks(size_t buflen, char *buffer) const bool AP_Parachute::get_legacy_relay_index(int8_t &index) const { // PARAMETER_CONVERSION - Added: Dec-2023 - if (!enabled() || (_release_type > AP_PARACHUTE_TRIGGER_TYPE_RELAY_3)) { + if (_release_type > AP_PARACHUTE_TRIGGER_TYPE_RELAY_3) { + // Not relay type + return false; + } + if (!enabled() && !_enabled.configured()) { + // Disabled and parameter never changed + // Copter manual parachute release enables and deploys in one step + // This means it is possible for parachute to still function correctly if disabled at boot + // Checking if the enable param is configured means the user must have setup chute at some point + // this means relay parm conversion will be done if parachute has ever been enabled + // Parachute has priority in relay param conversion, so this might mean we overwrite some other function return false; } index = _release_type; diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.cpp index bf286f8985aaec..d35d12d0e2b434 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.cpp @@ -20,11 +20,6 @@ #include "AP_RCProtocol_IBUS.h" -// constructor -AP_RCProtocol_IBUS::AP_RCProtocol_IBUS(AP_RCProtocol &_frontend) : - AP_RCProtocol_Backend(_frontend) -{} - // decode a full IBUS frame bool AP_RCProtocol_IBUS::ibus_decode(const uint8_t frame[IBUS_FRAME_SIZE], uint16_t *values, bool *ibus_failsafe) { diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.h b/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.h index b3e759781662ae..179eb22e22032b 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.h +++ b/libraries/AP_RCProtocol/AP_RCProtocol_IBUS.h @@ -30,7 +30,8 @@ class AP_RCProtocol_IBUS : public AP_RCProtocol_Backend { public: - AP_RCProtocol_IBUS(AP_RCProtocol &_frontend); + using AP_RCProtocol_Backend::AP_RCProtocol_Backend; + void process_pulse(uint32_t width_s0, uint32_t width_s1) override; void process_byte(uint8_t byte, uint32_t baudrate) override; private: diff --git a/libraries/AP_Scripting/docs/docs.lua b/libraries/AP_Scripting/docs/docs.lua index f31e6a8ebf623a..b77fac9b9a3988 100644 --- a/libraries/AP_Scripting/docs/docs.lua +++ b/libraries/AP_Scripting/docs/docs.lua @@ -1221,7 +1221,6 @@ compass = {} ---@return boolean function compass:healthy(instance) end - -- desc ---@class camera camera = {} @@ -1506,6 +1505,7 @@ function ins:get_gyro_health(instance) end ---@return boolean function ins:get_accel_health(instance) end + -- Get the value of a specific gyroscope ---@param instance integer -- the 0-based index of the gyroscope instance to return. ---@return Vector3f_ud @@ -1516,6 +1516,11 @@ function ins:get_gyro(instance) end ---@return Vector3f_ud function ins:get_accel(instance) end +-- Get if the INS is currently calibrating +---@return boolean +function ins:calibrating() end + + -- desc ---@class Motors_dynamic Motors_dynamic = {} @@ -3382,6 +3387,14 @@ fs = {} ---@return stat_t_ud|nil function fs:stat(param1) end +-- Format the SD card. This is a async operation, use get_format_status to get the status of the format +---@return boolean +function fs:format() end + +-- Get the current status of a format. 0=NOT_STARTED, 1=PENDING, 2=IN_PROGRESS, 3=SUCCESS, 4=FAILURE +---@return number +function fs:get_format_status() end + -- desc ---@class networking networking = {} diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index 33af2745fcbb79..289697349f2c9b 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -635,6 +635,7 @@ singleton AP_InertialSensor method get_gyro_health boolean uint8_t'skip_check singleton AP_InertialSensor method get_accel_health boolean uint8_t'skip_check singleton AP_InertialSensor method get_gyro Vector3f uint8_t'skip_check singleton AP_InertialSensor method get_accel Vector3f uint8_t'skip_check +singleton AP_InertialSensor method calibrating boolean singleton CAN manual get_device lua_get_CAN_device 1 singleton CAN manual get_device2 lua_get_CAN_device2 1 @@ -883,6 +884,8 @@ userdata AP_Filesystem::stat_t method is_directory boolean singleton AP_Filesystem rename fs singleton AP_Filesystem method stat boolean string AP_Filesystem::stat_t'Null +singleton AP_Filesystem method format boolean +singleton AP_Filesystem method get_format_status uint8_t'skip_check include AP_RTC/AP_RTC.h depends AP_RTC_ENABLED include AP_RTC/AP_RTC_config.h diff --git a/libraries/AP_Vehicle/AP_Vehicle.cpp b/libraries/AP_Vehicle/AP_Vehicle.cpp index c138c19d79a2a5..fcb78c2799e712 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.cpp +++ b/libraries/AP_Vehicle/AP_Vehicle.cpp @@ -258,6 +258,12 @@ const AP_Param::GroupInfo AP_Vehicle::var_info[] = { AP_SUBGROUPINFO(stats, "STAT", 27, AP_Vehicle, AP_Stats), #endif +#if AP_SCRIPTING_ENABLED + // @Group: SCR_ + // @Path: ../AP_Scripting/AP_Scripting.cpp + AP_SUBGROUPINFO(scripting, "SCR_", 28, AP_Vehicle, AP_Scripting), +#endif + AP_GROUPEND }; @@ -367,6 +373,10 @@ void AP_Vehicle::setup() // init_ardupilot is where the vehicle does most of its initialisation. init_ardupilot(); +#if AP_SCRIPTING_ENABLED + scripting.init(); +#endif // AP_SCRIPTING_ENABLED + #if AP_AIRSPEED_ENABLED airspeed.init(); if (airspeed.enabled()) { @@ -976,10 +986,7 @@ void AP_Vehicle::one_Hz_update(void) } #if AP_SCRIPTING_ENABLED - AP_Scripting *scripting = AP_Scripting::get_singleton(); - if (scripting != nullptr) { - scripting->update(); - } + scripting.update(); #endif } diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 32e0f3150cb953..3e38ac9b63691c 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -69,6 +69,9 @@ #include #include #include // statistics library +#if AP_SCRIPTING_ENABLED +#include +#endif class AP_DDS_Client; @@ -415,6 +418,10 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks { AP_TemperatureSensor temperature_sensor; #endif +#if AP_SCRIPTING_ENABLED + AP_Scripting scripting; +#endif + static const struct AP_Param::GroupInfo var_info[]; static const struct AP_Scheduler::Task scheduler_tasks[];