mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Scripting: use get_uint32 instead of luaL_checkinteger
This commit is contained in:
parent
3f7892fc79
commit
06b5400d0b
@ -347,7 +347,7 @@ void AP_Scripting::handle_message(const mavlink_message_t &msg, const mavlink_ch
|
||||
|
||||
WITH_SEMAPHORE(mavlink_data.sem);
|
||||
for (uint16_t i = 0; i < mavlink_data.accept_msg_ids_size; i++) {
|
||||
if (mavlink_data.accept_msg_ids[i] == -1) {
|
||||
if (mavlink_data.accept_msg_ids[i] == UINT32_MAX) {
|
||||
return;
|
||||
}
|
||||
if (mavlink_data.accept_msg_ids[i] == msg.msgid) {
|
||||
|
@ -105,12 +105,9 @@ public:
|
||||
uint32_t timestamp_ms;
|
||||
};
|
||||
|
||||
static const int mavlink_input_queue_size = 5;
|
||||
static const int mavlink_output_queue_size = 3;
|
||||
|
||||
struct mavlink {
|
||||
ObjectBuffer<struct mavlink_msg> *rx_buffer;
|
||||
int *accept_msg_ids;
|
||||
uint32_t *accept_msg_ids;
|
||||
uint16_t accept_msg_ids_size;
|
||||
HAL_Semaphore sem;
|
||||
} mavlink_data;
|
||||
|
@ -43,9 +43,9 @@ int lua_mavlink_init(lua_State *L) {
|
||||
binding_argcheck(L, 2);
|
||||
WITH_SEMAPHORE(AP::scripting()->mavlink_data.sem);
|
||||
// get the depth of receive queue
|
||||
const int queue_size = luaL_checkinteger(L, -1);
|
||||
const uint32_t queue_size = get_uint32(L, -1, 0, 25);
|
||||
// get number of msgs to accept
|
||||
const int num_msgs = luaL_checkinteger(L, -2);
|
||||
const uint32_t num_msgs = get_uint32(L, -2, 0, 25);
|
||||
|
||||
struct AP_Scripting::mavlink &data = AP::scripting()->mavlink_data;
|
||||
if (data.rx_buffer == nullptr) {
|
||||
@ -55,12 +55,12 @@ int lua_mavlink_init(lua_State *L) {
|
||||
}
|
||||
}
|
||||
if (data.accept_msg_ids == nullptr) {
|
||||
data.accept_msg_ids = new int[num_msgs];
|
||||
data.accept_msg_ids = new uint32_t[num_msgs];
|
||||
if (data.accept_msg_ids == nullptr) {
|
||||
return luaL_error(L, "Failed to allocate mavlink rx registry");
|
||||
}
|
||||
data.accept_msg_ids_size = num_msgs;
|
||||
memset(data.accept_msg_ids, -1, sizeof(int) * num_msgs);
|
||||
memset(data.accept_msg_ids, UINT32_MAX, sizeof(int) * num_msgs);
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
@ -92,8 +92,7 @@ int lua_mavlink_receive_chan(lua_State *L) {
|
||||
int lua_mavlink_register_rx_msgid(lua_State *L) {
|
||||
binding_argcheck(L, 1);
|
||||
|
||||
const int msgid = luaL_checkinteger(L, -1);
|
||||
luaL_argcheck(L, ((msgid >= 0) && (msgid < (1 << 24))), 1, "msgid out of range");
|
||||
const uint32_t msgid = get_uint32(L, -1, 0, (1 << 24) - 1);
|
||||
|
||||
struct AP_Scripting::mavlink &data = AP::scripting()->mavlink_data;
|
||||
|
||||
@ -107,7 +106,7 @@ int lua_mavlink_register_rx_msgid(lua_State *L) {
|
||||
|
||||
int i = 0;
|
||||
for (i = 0; i < data.accept_msg_ids_size; i++) {
|
||||
if (data.accept_msg_ids[i] == -1) {
|
||||
if (data.accept_msg_ids[i] == UINT32_MAX) {
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -128,11 +127,9 @@ int lua_mavlink_register_rx_msgid(lua_State *L) {
|
||||
int lua_mavlink_send_chan(lua_State *L) {
|
||||
binding_argcheck(L, 3);
|
||||
|
||||
const mavlink_channel_t chan = (mavlink_channel_t)luaL_checkinteger(L, 1);
|
||||
luaL_argcheck(L, (chan < MAVLINK_COMM_NUM_BUFFERS), 1, "channel out of range");
|
||||
const mavlink_channel_t chan = (mavlink_channel_t)get_uint32(L, 1, 0, MAVLINK_COMM_NUM_BUFFERS - 1);
|
||||
|
||||
const int msgid = luaL_checkinteger(L, 2);
|
||||
luaL_argcheck(L, ((msgid >= 0) && (msgid < (1 << 24))), 2, "msgid out of range");
|
||||
const uint32_t msgid = get_uint32(L, 2, 0, (1 << 24) - 1);
|
||||
|
||||
const char *packet = luaL_checkstring(L, 3);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user