AP_Scripting: change mavlink to :
access to match everything else, return timestamp as uint32
This commit is contained in:
parent
7a99fd7e3b
commit
529fb83ce3
@ -44,12 +44,16 @@ int lua_micros(lua_State *L) {
|
||||
}
|
||||
|
||||
int lua_mavlink_init(lua_State *L) {
|
||||
binding_argcheck(L, 2);
|
||||
|
||||
// Allow : and . access
|
||||
const int arg_offset = (luaL_testudata(L, 1, "mavlink") != NULL) ? 1 : 0;
|
||||
|
||||
binding_argcheck(L, 2+arg_offset);
|
||||
WITH_SEMAPHORE(AP::scripting()->mavlink_data.sem);
|
||||
// get the depth of receive queue
|
||||
const uint32_t queue_size = get_uint32(L, -1, 0, 25);
|
||||
const uint32_t queue_size = get_uint32(L, 1+arg_offset, 0, 25);
|
||||
// get number of msgs to accept
|
||||
const uint32_t num_msgs = get_uint32(L, -2, 0, 25);
|
||||
const uint32_t num_msgs = get_uint32(L, 2+arg_offset, 0, 25);
|
||||
|
||||
struct AP_Scripting::mavlink &data = AP::scripting()->mavlink_data;
|
||||
if (data.rx_buffer == nullptr) {
|
||||
@ -70,7 +74,11 @@ int lua_mavlink_init(lua_State *L) {
|
||||
}
|
||||
|
||||
int lua_mavlink_receive_chan(lua_State *L) {
|
||||
binding_argcheck(L, 0);
|
||||
|
||||
// Allow : and . access
|
||||
const int arg_offset = (luaL_testudata(L, 1, "mavlink") != NULL) ? 1 : 0;
|
||||
|
||||
binding_argcheck(L, arg_offset);
|
||||
|
||||
struct AP_Scripting::mavlink_msg msg;
|
||||
ObjectBuffer<struct AP_Scripting::mavlink_msg> *rx_buffer = AP::scripting()->mavlink_data.rx_buffer;
|
||||
@ -85,7 +93,8 @@ int lua_mavlink_receive_chan(lua_State *L) {
|
||||
luaL_addlstring(&b, (char *)&msg.msg, sizeof(msg.msg));
|
||||
luaL_pushresult(&b);
|
||||
lua_pushinteger(L, msg.chan);
|
||||
lua_pushinteger(L, msg.timestamp_ms);
|
||||
new_uint32_t(L);
|
||||
*check_uint32_t(L, -1) = msg.timestamp_ms;
|
||||
return 3;
|
||||
} else {
|
||||
// no MAVLink to handle, just return no results
|
||||
@ -94,9 +103,13 @@ int lua_mavlink_receive_chan(lua_State *L) {
|
||||
}
|
||||
|
||||
int lua_mavlink_register_rx_msgid(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
|
||||
const uint32_t msgid = get_uint32(L, -1, 0, (1 << 24) - 1);
|
||||
|
||||
// Allow : and . access
|
||||
const int arg_offset = (luaL_testudata(L, 1, "mavlink") != NULL) ? 1 : 0;
|
||||
|
||||
binding_argcheck(L, 1+arg_offset);
|
||||
|
||||
const uint32_t msgid = get_uint32(L, 1+arg_offset, 0, (1 << 24) - 1);
|
||||
|
||||
struct AP_Scripting::mavlink &data = AP::scripting()->mavlink_data;
|
||||
|
||||
@ -129,13 +142,17 @@ int lua_mavlink_register_rx_msgid(lua_State *L) {
|
||||
}
|
||||
|
||||
int lua_mavlink_send_chan(lua_State *L) {
|
||||
binding_argcheck(L, 3);
|
||||
|
||||
// Allow : and . access
|
||||
const int arg_offset = (luaL_testudata(L, 1, "mavlink") != NULL) ? 1 : 0;
|
||||
|
||||
binding_argcheck(L, 3+arg_offset);
|
||||
|
||||
const mavlink_channel_t chan = (mavlink_channel_t)get_uint32(L, 1, 0, MAVLINK_COMM_NUM_BUFFERS - 1);
|
||||
const mavlink_channel_t chan = (mavlink_channel_t)get_uint32(L, 1+arg_offset, 0, MAVLINK_COMM_NUM_BUFFERS - 1);
|
||||
|
||||
const uint32_t msgid = get_uint32(L, 2, 0, (1 << 24) - 1);
|
||||
const uint32_t msgid = get_uint32(L, 2+arg_offset, 0, (1 << 24) - 1);
|
||||
|
||||
const char *packet = luaL_checkstring(L, 3);
|
||||
const char *packet = luaL_checkstring(L, 3+arg_offset);
|
||||
|
||||
// FIXME: The data that's in this mavlink_msg_entry_t should be provided from the script, which allows
|
||||
// sending entirely new messages as outputs. At the moment we can only encode messages that
|
||||
|
Loading…
Reference in New Issue
Block a user