AP_Scripting: Add access to SRV_Channels::set_output_pwm

This also provides a more intresting function, with range checking. We
could choose to ignore this range checking and leave the script author
responsible for managing this, but it's probably better to protect the
author from themselves as much as possible, even if it makes the API
binding harder to automate
This commit is contained in:
Michael du Breuil 2018-10-29 23:01:15 -07:00 committed by WickedShell
parent ac63e55c8d
commit a2a8ac15b3
2 changed files with 32 additions and 0 deletions

View File

@ -1,5 +1,6 @@
#include <AP_Common/AP_Common.h>
#include <GCS_MAVLink/GCS.h>
#include <SRV_Channel/SRV_Channel.h>
#include "lua_bindings.h"
@ -15,9 +16,37 @@ static const luaL_Reg gcs_functions[] =
{NULL, NULL}
};
int lua_servo_set_output_pwm(lua_State *state) {
int servo_function = luaL_checkinteger(state, 1);
int output_value = luaL_checknumber(state, 2);
// range check the output function
if ((servo_function < SRV_Channel::Aux_servo_function_t::k_scripting1) ||
(servo_function > SRV_Channel::Aux_servo_function_t::k_scripting16)) {
return luaL_error(state, "Servo function (%d) is not a scriptable output", servo_function);
}
if (output_value > UINT16_MAX) {
return luaL_error(state, "Servo range (%d) is out of range", output_value);
}
SRV_Channels::set_output_pwm((SRV_Channel::Aux_servo_function_t)servo_function, output_value);
gcs().send_text(MAV_SEVERITY_INFO, "Set to %d", output_value);
return 0;
}
static const luaL_Reg servo_functions[] =
{
{"set_output_pwm", lua_servo_set_output_pwm},
{NULL, NULL}
};
void load_lua_bindings(lua_State *state) {
luaL_newlib(state, gcs_functions);
lua_setglobal(state, "gcs");
luaL_newlib(state, servo_functions);
lua_setglobal(state, "servo");
}
void hook(lua_State *L, lua_Debug *ar) {

View File

@ -27,6 +27,9 @@ function get_sandbox_env ()
utf8 = { char = utf8.char, charpattern = utf8.charpattern, codes = utf8.codes,
codepoint = utf8.codepoint, len = utf8.len, offsets = utf8.offsets},
os = { clock = os.clock, difftime = os.difftime, time = os.time },
-- ArduPilot specific
gcs = { send_text = gcs.send_text},
servo = { set_output_pwm = servo.set_output_pwm},
}
end