Skip to content

Commit

Permalink
AP_Scripting: added gcs:command_int() binding
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Jun 23, 2024
1 parent 2f93693 commit ae8b428
Show file tree
Hide file tree
Showing 5 changed files with 122 additions and 0 deletions.
7 changes: 7 additions & 0 deletions libraries/AP_Scripting/docs/docs.lua
Original file line number Diff line number Diff line change
Expand Up @@ -2585,6 +2585,13 @@ function gcs:send_text(severity, text) end
---@return uint32_t_ud -- system time in milliseconds
function gcs:last_seen() end

-- call a MAVLink MAV_CMD_xxx command via command_int interface
---@param frame integer -- MAV_FRAME_xxx
---@param command integer -- MAV_CMD_xxx
---@param params table -- parameters, including x, y and z
---@return boolean
function gcs:command_int(frame, command, params) end

-- The relay library provides access to controlling relay outputs.
relay = {}

Expand Down
48 changes: 48 additions & 0 deletions libraries/AP_Scripting/examples/command_int.lua
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
--[[
demonstrate using the gcs:command_int() interface to send commands from MAVLink MAV_CMD_xxx set
--]]

local MAV_FRAME_GLOBAL = 0

local MAV_CMD_DO_SET_MODE = 176
local MAV_CMD_DO_REPOSITION = 192

-- some plane flight modes for testing
local MODE_LOITER = 12
local MODE_GUIDED = 15

local MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1

--[[
test API calls. When in LOITER mode change to GUIDED and force flying to a location NE of home
--]]
local function test_command_int()
if vehicle:get_mode() ~= MODE_LOITER then
return
end
local home = ahrs:get_home()
if not home then
return
end

-- force mode GUIDED
gcs:command_int(MAV_FRAME_GLOBAL, MAV_CMD_DO_SET_MODE, { MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, MODE_GUIDED })

-- and fly to 200m NE of home and 100m above home
local dest = home:copy()
dest:offset_bearing(45, 200)
dest:alt(home:alt()+100*100)

gcs:command_int(MAV_FRAME_GLOBAL, MAV_CMD_DO_REPOSITION, { -1, 0, 0, 0,
x = dest:lat(),
y = dest:lng(),
z = dest:alt()*0.01 })
end

local function update()
test_command_int()
return update, 1000
end

return update, 1000

1 change: 1 addition & 0 deletions libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -296,6 +296,7 @@ singleton GCS method get_high_latency_status depends HAL_HIGH_LATENCY2_ENABLED =

singleton GCS method enable_high_latency_connections void boolean
singleton GCS method enable_high_latency_connections depends HAL_HIGH_LATENCY2_ENABLED == 1
singleton GCS manual command_int lua_GCS_command_int 3 1

include AP_ONVIF/AP_ONVIF.h depends ENABLE_ONVIF == 1
singleton AP_ONVIF depends ENABLE_ONVIF == 1
Expand Down
65 changes: 65 additions & 0 deletions libraries/AP_Scripting/lua_bindings.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1025,4 +1025,69 @@ void lua_abort()
#endif
}

#if HAL_GCS_ENABLED
/*
implement gcs:command_int() access to MAV_CMD_xxx commands
*/
int lua_GCS_command_int(lua_State *L)
{
GCS *_gcs = check_GCS(L);
binding_argcheck(L, 4);

const uint16_t frame = get_uint8_t(L, 2);
const uint16_t command = get_uint16_t(L, 3);
if (!lua_istable(L, 4)) {
// must have parameter table
return 0;
}

mavlink_command_int_t pkt {};

pkt.frame = frame;
pkt.command = command;

float *params = &pkt.param1;
int32_t *xy = &pkt.x;

// extract the first 4 parameters as floats
for (uint8_t i=0; i<4; i++) {
lua_pushinteger(L, i+1);
lua_gettable(L, 4);
if (lua_isnumber(L, -1)) {
params[i] = lua_tonumber(L, -1);
}
lua_pop(L, 1);
}

// extract the xy values
for (uint8_t i=0; i<2; i++) {
const char *names[] = { "x", "y" };
lua_pushstring(L, names[i]);
lua_gettable(L, 4);
if (lua_isinteger(L, -1)) {
xy[i] = lua_tointeger(L, -1);
}
lua_pop(L, 1);
}

// and z
lua_pushstring(L, "z");
lua_gettable(L, 4);
if (lua_isnumber(L, -1)) {
pkt.z = lua_tonumber(L, -1);
}
lua_pop(L, 1);

// call the interface
auto result = _gcs->lua_command_int_packet(pkt);

// map MAV_RESULT to a boolean
bool ok = result == MAV_RESULT_ACCEPTED;

lua_pushboolean(L, ok);

return 1;
}
#endif

#endif // AP_SCRIPTING_ENABLED
1 change: 1 addition & 0 deletions libraries/AP_Scripting/lua_bindings.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,3 +27,4 @@ int lua_mavlink_send_chan(lua_State *L);
int lua_mavlink_block_command(lua_State *L);
int lua_print(lua_State *L);
int lua_range_finder_handle_script_msg(lua_State *L);
int lua_GCS_command_int(lua_State *L);

0 comments on commit ae8b428

Please sign in to comment.