Compiling LUA scripting for 1M processors

All my FCs have 1M flash but I really want to try out LUA scripting, which doesn’t get enabled unless you have 2M. I have been able to reduce the size of the ArduRover code by removing features and devices I don’t need but I have not found a define to specifically enable LUA scripting. The only way I have found is to set the FLASH_SIZE in hwdef.dat to 2048. With that set, and the reduced features, I can get to a code size of 862k. However, when loaded into the FC, I am getting “Internal Error 0x800” and it is periodically resetting. I presume this is due to the watchdog.

Would appreciate any pointers in enabling LUA scripting.

FYI, I am trying this with ArduRover 4.3b4 code on an omnibusf4pro.

1 Like

You’ll have to neuter the firmware so badly that it’s probably not worth the time it takes to make this happen. For under $100 you can get an H743 based autopilot that will save you all of that time.

I hear you on the H743 FCs, but before I go there, I still want to give this a bit more effort. Given that I was able to trim it down to 862k code size with Scripting enabled and still keep all the features I need, I feel I am so close and am just missing some 2M dependency that is making it watchdog.

1 Like

Same here as for @splee777. I regret buying a 1MB flash flight controller, I will buy one with more flash for my next plane. At the moment I have much more time when I can fiddle with options when compiling at my computer than I have time to occupy the kitchen table for changing flight controllers. And those RC things that cost “just” 100$ tend to add up :slight_smile:

Hence I’m curious about an option for enabling LUA-scripting. Although my expectations of the scripts that will actually run are very low.

Part of your watchdog problem might be that you’ve removed or altered methods that are bound to the scripting engine, though the firmware may not build at all if that’s the case.

Should you get it working, I fear that all you’d be doing is reinventing the removed native features via scripting by enabling it on such a limited version of AP.

If you just want to experiment with Lua to see what might be possible, SITL is a great option.

I’m with you, Erik. I’m retired and have the luxury of going down rabbit holes just for the heck of it. I feel I’m so close that I just need someone with knowledge to point me in the right direction. As background, I used the custom builder to build a minimal version and then looked at the build files to see all the defines they turned off. I then included most of those defines in my hwdef.dat. WIth the FLASH_SIZE left at 1024, it compiles to about 600k and appears to run fine. When I set FLASH_SIZE to 2048, it compiles ok to 862k, but then reboots with Internal Error 0x800. FLASH_SIZE 2048 must have some dependencies beyond just deciding what additional features to include.

SITL would be a great option if all I wanted to do is play with lua, but this all started because I wanted to control some neopixel LEDs with scripting. I don’t need very fancy control. The standard firmware has a lot of un-needed devices and functions (for me anyway) and removing them saved a lot of code space. But I need scripting! :slight_smile:

You definitely need to find a way to activate lua while having FLASH_SIZE=1024.

Ok, so I found a kludge to include Lua scripting in the build for 1M boards. For now, it’s a brute force method that involves modifying Tools/ardupilotwaf/boards.py to always include scripting. Basically bypass the conditional check. From this conditional code:

        # Setup scripting, had to defer this to allow checking board size
        if ((not cfg.options.disable_scripting) and
            (not cfg.env.DISABLE_SCRIPTING) and
            ((cfg.env.BOARD_FLASH_SIZE is None) or
             (cfg.env.BOARD_FLASH_SIZE == []) or
             (cfg.env.BOARD_FLASH_SIZE > 1024))):

            env.DEFINES.update(
                AP_SCRIPTING_ENABLED = 1,
                LUA_32BITS = 1,
                )

            env.AP_LIBRARIES += [
                'AP_Scripting',
                'AP_Scripting/lua/src',
                ]

        else:
            cfg.options.disable_scripting = False


to just:

        # Setup scripting, had to defer this to allow checking board size
        env.DEFINES.update(
            AP_SCRIPTING_ENABLED = 1,
            LUA_32BITS = 1,
            )

        env.AP_LIBRARIES += [
            'AP_Scripting',
            'AP_Scripting/lua/src',
            ]

This will force ALL builds to always include scripting. Of course, you also have to reduce the size of your code to fit under 1M with scripting. To do that, include the following at the end of your hwdef.dat, adjusting it to the items you need.

define HAL_EXTERNAL_AHRS_ENABLED 0
define HAL_NAVEKF2_AVAILABLE 0
define HAL_NAVEKF3_AVAILABLE 1
define EK3_FEATURE_EXTERNAL_NAV 0
define HAL_INS_TEMPERATURE_CAL_ENABLE 0
define HAL_VISUALODOM_ENABLED 0
define HAL_PERIPH_SUPPORT_LONG_CAN_PRINTF 0
define AP_FETTEC_ONEWIRE_ENABLED 0
define AP_ROBOTISSERVO_ENABLED 0
define AP_VOLZ_ENABLED 0
define AP_AIRSPEED_ASP5033_ENABLED 0
define AP_AIRSPEED_ANALOG_ENABLED 0
define AP_AIRSPEED_DLVR_ENABLED 0
define AP_AIRSPEED_MS4525_ENABLED 0
define AP_AIRSPEED_MS5525_ENABLED 0
define AP_AIRSPEED_MSP_ENABLED 0
define AP_AIRSPEED_NMEA_ENABLED 0
define AP_AIRSPEED_SDP3X_ENABLED 0
define AP_AIRSPEED_UAVCAN_ENABLED 0
define AP_BATTMON_FUELFLOW_ENABLE 0
define AP_BATTMON_FUELLEVEL_ANALOG_ENABLE 0
define AP_BATTMON_FUELLEVEL_PWM_ENABLE 0
define HAL_BATTMON_INA2XX_ENABLED 0
define AP_BATTMON_SMBUS_ENABLE 0
define HAL_RUNCAM_ENABLED 0
define MODE_FLIP_ENABLED 0
define MODE_FLOWHOLD_ENABLED 0
define MODE_FOLLOW_ENABLED 0
define MODE_GUIDED_NOGPS_ENABLED 0
define MODE_SPORT_ENABLED 0
define MODE_SYSTEMID_ENABLED 0
define MODE_TURTLE_ENABLED 0
define MODE_ZIGZAG_ENABLED 0
define HAL_PICCOLO_CAN_ENABLE 0
define HAL_TORQEEDO_ENABLED 0
define AP_GPS_ERB_ENABLED 0
define AP_GPS_GSOF_ENABLED 0
define AP_GPS_MAV_ENABLED 0
define AP_GPS_NMEA_ENABLED 0
define AP_GPS_NOVA_ENABLED 0
define AP_GPS_SBF_ENABLED 0
define AP_GPS_SBP_ENABLED 0
define AP_GPS_SBP2_ENABLED 0
define AP_GPS_SIRF_ENABLED 0
define AP_GPS_UBLOX_ENABLED 1
define HAL_MOUNT_ALEXMOS_ENABLED 0
define HAL_MOUNT_GREMSY_ENABLED 0
define HAL_MOUNT_ENABLED 0
define HAL_MOUNT_SERVO_ENABLED 0
define HAL_MOUNT_SIYI_ENABLED 0
define HAL_SOLO_GIMBAL_ENABLED 0
define HAL_MOUNT_STORM32MAVLINK_ENABLED 0
define HAL_MOUNT_STORM32SERIAL_ENABLED 0
define HAL_EFI_ENABLED 0
define HAL_EFI_CURRAWONG_ECU_ENABLED 0
define HAL_EFI_DRONECAN_ENABLED 0
define HAL_EFI_NWPWU_ENABLED 0
define HAL_GENERATOR_ENABLED 0
define AP_ICENGINE_ENABLED 0
define HAL_ADSB_ENABLED 0
define HAL_ADSB_SAGETECH_ENABLED 0
define HAL_ADSB_SAGETECH_MXS_ENABLED 0
define HAL_ADSB_UAVIONIX_MAVLINK_ENABLED 0
define HAL_ADSB_UCP_ENABLED 0
define AP_AIS_ENABLED 0
define HAL_MSP_ENABLED 0
define HAL_MSP_COMPASS_ENABLED 0
define HAL_WITH_MSP_DISPLAYPORT 0
define HAL_MSP_GPS_ENABLED 0
define HAL_MSP_OPTICALFLOW_ENABLED 0
define HAL_MSP_RANGEFINDER_ENABLED 0
define HAL_MSP_SENSORS_ENABLED 0
# define OSD_ENABLED 0
define OSD_PARAM_ENABLED 0
define HAL_OSD_SIDEBAR_ENABLE 0
define HAL_PLUSCODE_ENABLE 0
define HAL_BARO_WIND_COMP_ENABLED 0
define HAL_DISPLAY_ENABLED 0
# define HAL_GYROFFT_ENABLED 0
define HAL_NMEA_OUTPUT_ENABLED 0
define AP_CAMERA_ENABLED 0
define AP_GRIPPER_ENABLED 0
define LANDING_GEAR_ENABLED 0
define HAL_SPRAYER_ENABLED 0
define WINCH_ENABLED 0
define HAL_LANDING_DEEPSTALL_ENABLED 0
define HAL_QUADPLANE_ENABLED 0
define HAL_SOARING_ENABLED 0
define AP_RANGEFINDER_ENABLED 0
define AP_RANGEFINDER_ANALOG_ENABLED 0
define AP_RANGEFINDER_BENEWAKE_CAN_ENABLED 0
define AP_RANGEFINDER_BENEWAKE_TF02_ENABLED 0
define AP_RANGEFINDER_BENEWAKE_TF03_ENABLED 0
define AP_RANGEFINDER_BENEWAKE_TFMINI_ENABLED 0
define AP_RANGEFINDER_BENEWAKE_TFMINIPLUS_ENABLED 0
define AP_RANGEFINDER_BLPING_ENABLED 0
define AP_RANGEFINDER_GYUS42V2_ENABLED 0
define AP_RANGEFINDER_HC_SR04_ENABLED 0
define AP_RANGEFINDER_LANBAO_ENABLED 0
define AP_RANGEFINDER_LEDDARONE_ENABLED 0
define AP_RANGEFINDER_LEDDARVU8_ENABLED 0
define AP_RANGEFINDER_LIGHTWARE_SERIAL_ENABLED 0
define AP_RANGEFINDER_LWI2C_ENABLED 0
define AP_RANGEFINDER_MAVLINK_ENABLED 0
define AP_RANGEFINDER_MAXBOTIX_SERIAL_ENABLED 0
define AP_RANGEFINDER_MAXSONARI2CXL_ENABLED 0
define AP_RANGEFINDER_NMEA_ENABLED 0
define AP_RANGEFINDER_PULSEDLIGHTLRF_ENABLED 0
define AP_RANGEFINDER_PWM_ENABLED 0
define AP_RANGEFINDER_TRI2C_ENABLED 0
define AP_RANGEFINDER_TERARANGER_SERIAL_ENABLED 0
define AP_RANGEFINDER_UAVCAN_ENABLED 0
define AP_RANGEFINDER_USD1_CAN_ENABLED 0
define AP_RANGEFINDER_USD1_SERIAL_ENABLED 0
define AP_RANGEFINDER_VL53L0X_ENABLED 0
define AP_RANGEFINDER_VL53L1X_ENABLED 0
define AP_RANGEFINDER_WASP_ENABLED 0
define AC_AVOID_ENABLED 0
define AC_OAPATHPLANNER_ENABLED 0
define AP_FENCE_ENABLED 0
define HAL_PARACHUTE_ENABLED 0
define HAL_PROXIMITY_ENABLED 0
define AP_AIRSPEED_ENABLED 0
define BEACON_ENABLED 0
define AP_BARO_BMP085_ENABLED 0
define AP_BARO_BMP280_ENABLED 1
define AP_BARO_BMP388_ENABLED 1
define AP_BARO_DPS280_ENABLED 0
define AP_BARO_DUMMY_ENABLED 0
define AP_BARO_EXTERNALAHRS_ENABLED 0
define AP_BARO_FBM320_ENABLED 0
define GPS_MOVING_BASELINE 0
define AP_BARO_ICM20789_ENABLED 0
define AP_BARO_ICP101XX_ENABLED 0
define AP_BARO_ICP201XX_ENABLED 0
define AP_BARO_KELLERLD_ENABLED 0
define AP_BARO_LPS2XH_ENABLED 0
define AP_BARO_MS56XX_ENABLED 0
define AP_BARO_MSP_ENABLED 0
define AP_OPTICALFLOW_ENABLED 0
define AP_OPTICALFLOW_CXOF_ENABLED 0
define AP_OPTICALFLOW_HEREFLOW_ENABLED 0
define AP_OPTICALFLOW_MAV_ENABLED 0
define AP_OPTICALFLOW_ONBOARD_ENABLED 0
define AP_OPTICALFLOW_PIXART_ENABLED 0
define AP_OPTICALFLOW_PX4FLOW_ENABLED 0
define AP_OPTICALFLOW_UPFLOW_ENABLED 0
define AP_RPM_EFI_ENABLED 0
define AP_RPM_ESC_TELEM_ENABLED 0
define AP_RPM_GENERATOR_ENABLED 0
define AP_RPM_HARMONICNOTCH_ENABLED 0
define AP_RPM_PIN_ENABLED 0
define AP_BARO_SPL06_ENABLED 0
define AP_TEMPERATURE_SENSOR_ENABLED 0
define AP_TEMPERATURE_SENSOR_MCP9600_ENABLED 0
define AP_TEMPERATURE_SENSOR_TSYS01_ENABLED 0
define AP_BARO_UAVCAN_ENABLED 0
define AP_RC_CHANNEL_AUX_FUNCTION_STRINGS_ENABLED 0
define HAL_CRSF_TELEM_ENABLED 0
define HAL_CRSF_TELEM_TEXT_SELECTION_ENABLED 0
define HAL_HIGH_LATENCY2_ENABLED 0
define HAL_HOTT_TELEM_ENABLED 0
define AP_LTM_TELEM_ENABLED 0
define HAL_SPEKTRUM_TELEM_ENABLED 0
define AP_MOTORS_FRAME_DECA_ENABLED 0
define AP_MOTORS_FRAME_DODECAHEXA_ENABLED 0
define AP_MOTORS_FRAME_HEXA_ENABLED 0
define AP_MOTORS_FRAME_OCTA_ENABLED 0
define AP_MOTORS_FRAME_OCTAQUAD_ENABLED 0
define AP_MOTORS_FRAME_QUAD_ENABLED 0
define AP_MOTORS_FRAME_Y6_ENABLED 0
define HAL_SMARTAUDIO_ENABLED 0
define AP_TRAMP_ENABLED 1

The above is the configuration I used for my ArduRover F405 FC. It compiles to about 830K.

So, the good news is that it compiles fine and Scripting is included in the code and it appears to run ok. The bad news, at least for F405 based processors is that there doesn’t seem to be enough RAM (192k) for scripting to run. I get a PreArm: Scripting: out of memory error, and no amount of playing with the SCR_HEAP_SIZE can get rid of it. Changing it also doesn’t affect freemem, which shows about 34k free, so something is off. I’m on a trip right now (had brought a Macbook and F405 with me for testing!) and can only test with it, but when I get back home in a few days, I will test with a F745 processor, which has 320K ram.

1 Like

Yes, that is a better solution than your previous change.

Peter Barker is doing a great job at selectively disabling features, so maybe at some point the F405 processor will be able to do it.

I can report back that Lua Scripting appears to run successfully in a F745 1M flight controller. Unfortunately, the F405 processors do not appear to have enough ram memory to run it properly, but hey, you can’t win them all…

*Edit: I should also add that you should not disable AP_FENCE_ENABLE otherwise Waypoints won’t work.

1 Like

Well, after a couple of days with playing with scripts, I will say that they certainly work well enough for what I need. I don’t know what functions you may want to implement, but I am only using them to check ground steering and throttle to implement neopixel LED turn signals and brake lights, as well as turn on and off headlights via RC input. The functions available should allow you to do a lot more if you so desire. It basically allows you to extend Ardupilot functions without having to modify core code. The F745 has enough memory where I didn’t have to delete SRTL waypoints to free up memory either, but then I only have a simple script running. I don’t know when the memory limits will be reached.

I can’t say I’m a fan of Lua, but it’s better than nothing and let me get the job done!

1 Like