mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: Disable by default, fix a nullable type, update README
This commit is contained in:
parent
ccbf3234f7
commit
0ed3c547fd
@ -44,7 +44,7 @@ const AP_Param::GroupInfo AP_Scripting::var_info[] = {
|
||||
// @Values: 0:None,1:Lua Scripts
|
||||
// @RebootRequired: True
|
||||
// @User: Advanced
|
||||
AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Scripting, _enable, 1, AP_PARAM_FLAG_ENABLE),
|
||||
AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Scripting, _enable, 0, AP_PARAM_FLAG_ENABLE),
|
||||
|
||||
// @Param: VM_I_COUNT
|
||||
// @DisplayName: Scripting Virtual Machine Instruction Count
|
||||
|
@ -2,13 +2,15 @@
|
||||
|
||||
## Enabling Scripting Support in Builds
|
||||
|
||||
To enable scripting the `--enable-scripting` flag must be passed to waf.
|
||||
The following example enables scripting and builds the ArduPlane firmware for the Cube.
|
||||
Scripting is automatically enabled on all boards with at least 1MB of flash space.
|
||||
The following example enables scripting, builds the ArduPlane firmware for the Cube, and uploads it.
|
||||
|
||||
```
|
||||
$ waf configure --enable-scripting --board=CubeBlack
|
||||
$ waf configure --board=CubeBlack
|
||||
|
||||
$ waf plane
|
||||
|
||||
$ waf plane --upload
|
||||
```
|
||||
|
||||
To run SITL you can simply use the `sim_vehicle.py` script which will wrap the configuration, compilation,
|
||||
@ -16,9 +18,11 @@ and launching of the simulation into one command for you.
|
||||
|
||||
|
||||
```
|
||||
$ Tools/autotest/sim_vehicle.py --waf-configure-arg --enable-scripting -v ArduPlane
|
||||
$ Tools/autotest/sim_vehicle.py -v ArduPlane
|
||||
```
|
||||
|
||||
Once you have a vehicle flashed with scripting you need to set the `SCR_ENABLE` parameter to 1 to enable scripting and reboot.
|
||||
|
||||
## Adding Scripts
|
||||
|
||||
The vehicle will automatically look for and launch any scripts that are contained in the `scripts` folder when it starts.
|
||||
|
@ -11,7 +11,7 @@ userdata Location field loiter_xtrack boolean read write
|
||||
|
||||
userdata Location method get_distance float Location
|
||||
userdata Location method offset void float -FLT_MAX FLT_MAX float -FLT_MAX FLT_MAX
|
||||
userdata Location method get_vector_from_origin_NEU boolean Vector3f
|
||||
userdata Location method get_vector_from_origin_NEU boolean Vector3f'Null
|
||||
|
||||
include AP_AHRS/AP_AHRS.h
|
||||
|
||||
|
@ -388,13 +388,18 @@ static int Vector3f___sub(lua_State *L) {
|
||||
|
||||
static int Location_get_vector_from_origin_NEU(lua_State *L) {
|
||||
// 1 Vector3f 14 : 6
|
||||
binding_argcheck(L, 2);
|
||||
binding_argcheck(L, 1);
|
||||
Location * ud = check_Location(L, 1);
|
||||
Vector3f & data_2 = *check_Vector3f(L, 2);
|
||||
Vector3f data_5002 = {};
|
||||
const bool data = ud->get_vector_from_origin_NEU(
|
||||
data_2);
|
||||
data_5002);
|
||||
|
||||
lua_pushboolean(L, data);
|
||||
if (data) {
|
||||
new_Vector3f(L);
|
||||
*check_Vector3f(L, -1) = data_5002;
|
||||
} else {
|
||||
lua_pushnil(L);
|
||||
}
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user