mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AP_Scripting: Protect send_text from reading the stack
Also fixes small alignment problem in generated code
This commit is contained in:
parent
81222fbde0
commit
9e04939adf
@ -132,4 +132,4 @@ singleton AP_Relay method toggle void uint8_t 0 AP_RELAY_NUM_RELAYS
|
|||||||
|
|
||||||
include GCS_MAVLink/GCS.h
|
include GCS_MAVLink/GCS.h
|
||||||
singleton GCS alias gcs
|
singleton GCS alias gcs
|
||||||
singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG string
|
singleton GCS method send_text void MAV_SEVERITY'enum MAV_SEVERITY_EMERGENCY MAV_SEVERITY_DEBUG "%s"'literal string
|
||||||
|
@ -1133,10 +1133,12 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
|||||||
arg = method->arguments;
|
arg = method->arguments;
|
||||||
arg_count = 2;
|
arg_count = 2;
|
||||||
while (arg != NULL) {
|
while (arg != NULL) {
|
||||||
// emit_checker will emit a nullable argument for us
|
if (arg->type.type != TYPE_LITERAL) {
|
||||||
emit_checker(arg->type, arg_count, " ", "argument");
|
// emit_checker will emit a nullable argument for us
|
||||||
|
emit_checker(arg->type, arg_count, " ", "argument");
|
||||||
|
arg_count++;
|
||||||
|
}
|
||||||
arg = arg->next;
|
arg = arg->next;
|
||||||
arg_count++;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (data->flags & UD_FLAG_SEMAPHORE) {
|
if (data->flags & UD_FLAG_SEMAPHORE) {
|
||||||
@ -1145,46 +1147,50 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
|||||||
|
|
||||||
switch (method->return_type.type) {
|
switch (method->return_type.type) {
|
||||||
case TYPE_BOOLEAN:
|
case TYPE_BOOLEAN:
|
||||||
fprintf(source, " const bool data = ud->%s(\n", method->name);
|
fprintf(source, " const bool data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_FLOAT:
|
case TYPE_FLOAT:
|
||||||
fprintf(source, " const float data = ud->%s(\n", method->name);
|
fprintf(source, " const float data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_INT8_T:
|
case TYPE_INT8_T:
|
||||||
fprintf(source, " const int8_t data = ud->%s(\n", method->name);
|
fprintf(source, " const int8_t data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_INT16_T:
|
case TYPE_INT16_T:
|
||||||
fprintf(source, " const int6_t data = ud->%s(\n", method->name);
|
fprintf(source, " const int6_t data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_INT32_T:
|
case TYPE_INT32_T:
|
||||||
fprintf(source, " const int32_t data = ud->%s(\n", method->name);
|
fprintf(source, " const int32_t data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_STRING:
|
case TYPE_STRING:
|
||||||
fprintf(source, " const char * data = ud->%s(\n", method->name);
|
fprintf(source, " const char * data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_UINT8_T:
|
case TYPE_UINT8_T:
|
||||||
fprintf(source, " const uint8_t data = ud->%s(\n", method->name);
|
fprintf(source, " const uint8_t data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_UINT16_T:
|
case TYPE_UINT16_T:
|
||||||
fprintf(source, " const uint16_t data = ud->%s(\n", method->name);
|
fprintf(source, " const uint16_t data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_UINT32_T:
|
case TYPE_UINT32_T:
|
||||||
fprintf(source, " const uint32_t data = ud->%s(\n", method->name);
|
fprintf(source, " const uint32_t data = ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_ENUM:
|
case TYPE_ENUM:
|
||||||
fprintf(source, " const %s &data = ud->%s(\n", method->return_type.data.enum_name, method->name);
|
fprintf(source, " const %s &data = ud->%s(", method->return_type.data.enum_name, method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_USERDATA:
|
case TYPE_USERDATA:
|
||||||
fprintf(source, " const %s &data = ud->%s(\n", method->return_type.data.userdata_name, method->name);
|
fprintf(source, " const %s &data = ud->%s(", method->return_type.data.userdata_name, method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_NONE:
|
case TYPE_NONE:
|
||||||
fprintf(source, " ud->%s(\n", method->name);
|
fprintf(source, " ud->%s(", method->name);
|
||||||
break;
|
break;
|
||||||
case TYPE_LITERAL:
|
case TYPE_LITERAL:
|
||||||
error(ERROR_USERDATA, "Can't return a literal from a method");
|
error(ERROR_USERDATA, "Can't return a literal from a method");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (arg_count != 2) {
|
||||||
|
fprintf(source, "\n");
|
||||||
|
}
|
||||||
|
|
||||||
arg = method->arguments;
|
arg = method->arguments;
|
||||||
arg_count = 2;
|
arg_count = 2;
|
||||||
while (arg != NULL) {
|
while (arg != NULL) {
|
||||||
@ -1209,13 +1215,15 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth
|
|||||||
error(ERROR_INTERNAL, "Can't pass nil as an argument");
|
error(ERROR_INTERNAL, "Can't pass nil as an argument");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
if (arg->type.type != TYPE_LITERAL) {
|
||||||
|
arg_count++;
|
||||||
|
}
|
||||||
arg = arg->next;
|
arg = arg->next;
|
||||||
if (arg != NULL) {
|
if (arg != NULL) {
|
||||||
fprintf(source, ",\n");
|
fprintf(source, ",\n");
|
||||||
}
|
}
|
||||||
arg_count++;
|
|
||||||
}
|
}
|
||||||
fprintf(source, "%s);\n\n", arg_count == 2 ? " " : "");
|
fprintf(source, "%s);\n\n", "");
|
||||||
|
|
||||||
if (data->flags & UD_FLAG_SEMAPHORE) {
|
if (data->flags & UD_FLAG_SEMAPHORE) {
|
||||||
fprintf(source, " ud->get_semaphore().give();\n");
|
fprintf(source, " ud->get_semaphore().give();\n");
|
||||||
|
@ -262,8 +262,7 @@ static int Location_lat(lua_State *L) {
|
|||||||
static int Vector2f_is_zero(lua_State *L) {
|
static int Vector2f_is_zero(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector2f * ud = check_Vector2f(L, 1);
|
Vector2f * ud = check_Vector2f(L, 1);
|
||||||
ud->is_zero(
|
ud->is_zero();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -271,8 +270,7 @@ static int Vector2f_is_zero(lua_State *L) {
|
|||||||
static int Vector2f_is_inf(lua_State *L) {
|
static int Vector2f_is_inf(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector2f * ud = check_Vector2f(L, 1);
|
Vector2f * ud = check_Vector2f(L, 1);
|
||||||
ud->is_inf(
|
ud->is_inf();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -280,8 +278,7 @@ static int Vector2f_is_inf(lua_State *L) {
|
|||||||
static int Vector2f_is_nan(lua_State *L) {
|
static int Vector2f_is_nan(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector2f * ud = check_Vector2f(L, 1);
|
Vector2f * ud = check_Vector2f(L, 1);
|
||||||
ud->is_nan(
|
ud->is_nan();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -289,8 +286,7 @@ static int Vector2f_is_nan(lua_State *L) {
|
|||||||
static int Vector2f_normalize(lua_State *L) {
|
static int Vector2f_normalize(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector2f * ud = check_Vector2f(L, 1);
|
Vector2f * ud = check_Vector2f(L, 1);
|
||||||
ud->normalize(
|
ud->normalize();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -298,8 +294,7 @@ static int Vector2f_normalize(lua_State *L) {
|
|||||||
static int Vector2f_length(lua_State *L) {
|
static int Vector2f_length(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector2f * ud = check_Vector2f(L, 1);
|
Vector2f * ud = check_Vector2f(L, 1);
|
||||||
const float data = ud->length(
|
const float data = ud->length();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushnumber(L, data);
|
lua_pushnumber(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -326,8 +321,7 @@ static int Vector2f___sub(lua_State *L) {
|
|||||||
static int Vector3f_is_zero(lua_State *L) {
|
static int Vector3f_is_zero(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector3f * ud = check_Vector3f(L, 1);
|
Vector3f * ud = check_Vector3f(L, 1);
|
||||||
ud->is_zero(
|
ud->is_zero();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -335,8 +329,7 @@ static int Vector3f_is_zero(lua_State *L) {
|
|||||||
static int Vector3f_is_inf(lua_State *L) {
|
static int Vector3f_is_inf(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector3f * ud = check_Vector3f(L, 1);
|
Vector3f * ud = check_Vector3f(L, 1);
|
||||||
ud->is_inf(
|
ud->is_inf();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -344,8 +337,7 @@ static int Vector3f_is_inf(lua_State *L) {
|
|||||||
static int Vector3f_is_nan(lua_State *L) {
|
static int Vector3f_is_nan(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector3f * ud = check_Vector3f(L, 1);
|
Vector3f * ud = check_Vector3f(L, 1);
|
||||||
ud->is_nan(
|
ud->is_nan();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -353,8 +345,7 @@ static int Vector3f_is_nan(lua_State *L) {
|
|||||||
static int Vector3f_normalize(lua_State *L) {
|
static int Vector3f_normalize(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector3f * ud = check_Vector3f(L, 1);
|
Vector3f * ud = check_Vector3f(L, 1);
|
||||||
ud->normalize(
|
ud->normalize();
|
||||||
);
|
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
@ -362,8 +353,7 @@ static int Vector3f_normalize(lua_State *L) {
|
|||||||
static int Vector3f_length(lua_State *L) {
|
static int Vector3f_length(lua_State *L) {
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
Vector3f * ud = check_Vector3f(L, 1);
|
Vector3f * ud = check_Vector3f(L, 1);
|
||||||
const float data = ud->length(
|
const float data = ud->length();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushnumber(L, data);
|
lua_pushnumber(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -483,6 +473,7 @@ static int GCS_send_text(lua_State *L) {
|
|||||||
const char * data_3 = luaL_checkstring(L, 3);
|
const char * data_3 = luaL_checkstring(L, 3);
|
||||||
ud->send_text(
|
ud->send_text(
|
||||||
data_2,
|
data_2,
|
||||||
|
"%s",
|
||||||
data_3);
|
data_3);
|
||||||
|
|
||||||
return 0;
|
return 0;
|
||||||
@ -650,8 +641,7 @@ static int AP_Terrain_status(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const uint8_t data = ud->status(
|
const uint8_t data = ud->status();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushinteger(L, data);
|
lua_pushinteger(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -664,8 +654,7 @@ static int AP_Terrain_enabled(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const bool data = ud->enabled(
|
const bool data = ud->enabled();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -678,8 +667,7 @@ static int RangeFinder_num_sensors(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const uint8_t data = ud->num_sensors(
|
const uint8_t data = ud->num_sensors();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushinteger(L, data);
|
lua_pushinteger(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -706,8 +694,7 @@ static int AP_GPS_first_unconfigured_gps(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const uint8_t data = ud->first_unconfigured_gps(
|
const uint8_t data = ud->first_unconfigured_gps();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushinteger(L, data);
|
lua_pushinteger(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -720,8 +707,7 @@ static int AP_GPS_all_configured(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const bool data = ud->all_configured(
|
const bool data = ud->all_configured();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1047,8 +1033,7 @@ static int AP_GPS_primary_sensor(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const uint8_t data = ud->primary_sensor(
|
const uint8_t data = ud->primary_sensor();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushinteger(L, data);
|
lua_pushinteger(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1061,8 +1046,7 @@ static int AP_GPS_num_sensors(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const uint8_t data = ud->num_sensors(
|
const uint8_t data = ud->num_sensors();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushinteger(L, data);
|
lua_pushinteger(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1115,8 +1099,7 @@ static int AP_BattMonitor_has_failsafed(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const bool data = ud->has_failsafed(
|
const bool data = ud->has_failsafed();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1283,8 +1266,7 @@ static int AP_BattMonitor_num_instances(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const uint8_t data = ud->num_instances(
|
const uint8_t data = ud->num_instances();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushinteger(L, data);
|
lua_pushinteger(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1297,8 +1279,7 @@ static int AP_Arming_arm(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const bool data = ud->arm(
|
const bool data = ud->arm( AP_Arming::Method::SCRIPTING);
|
||||||
AP_Arming::Method::SCRIPTING);
|
|
||||||
|
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1311,8 +1292,7 @@ static int AP_Arming_is_armed(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const bool data = ud->is_armed(
|
const bool data = ud->is_armed();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1325,8 +1305,7 @@ static int AP_Arming_disarm(lua_State *L) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
const bool data = ud->disarm(
|
const bool data = ud->disarm();
|
||||||
);
|
|
||||||
|
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
return 1;
|
return 1;
|
||||||
@ -1340,8 +1319,7 @@ static int AP_AHRS_prearm_healthy(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const bool data = ud->prearm_healthy(
|
const bool data = ud->prearm_healthy();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
@ -1356,8 +1334,7 @@ static int AP_AHRS_home_is_set(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const bool data = ud->home_is_set(
|
const bool data = ud->home_is_set();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
lua_pushboolean(L, data);
|
lua_pushboolean(L, data);
|
||||||
@ -1416,8 +1393,7 @@ static int AP_AHRS_groundspeed_vector(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const Vector2f &data = ud->groundspeed_vector(
|
const Vector2f &data = ud->groundspeed_vector();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
new_Vector2f(L);
|
new_Vector2f(L);
|
||||||
@ -1433,8 +1409,7 @@ static int AP_AHRS_wind_estimate(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const Vector3f &data = ud->wind_estimate(
|
const Vector3f &data = ud->wind_estimate();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
new_Vector3f(L);
|
new_Vector3f(L);
|
||||||
@ -1471,8 +1446,7 @@ static int AP_AHRS_get_gyro(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const Vector3f &data = ud->get_gyro(
|
const Vector3f &data = ud->get_gyro();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
new_Vector3f(L);
|
new_Vector3f(L);
|
||||||
@ -1488,8 +1462,7 @@ static int AP_AHRS_get_home(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const Location &data = ud->get_home(
|
const Location &data = ud->get_home();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
new_Location(L);
|
new_Location(L);
|
||||||
@ -1527,8 +1500,7 @@ static int AP_AHRS_get_yaw(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const float data = ud->get_yaw(
|
const float data = ud->get_yaw();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
lua_pushnumber(L, data);
|
lua_pushnumber(L, data);
|
||||||
@ -1543,8 +1515,7 @@ static int AP_AHRS_get_pitch(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const float data = ud->get_pitch(
|
const float data = ud->get_pitch();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
lua_pushnumber(L, data);
|
lua_pushnumber(L, data);
|
||||||
@ -1559,8 +1530,7 @@ static int AP_AHRS_get_roll(lua_State *L) {
|
|||||||
|
|
||||||
binding_argcheck(L, 1);
|
binding_argcheck(L, 1);
|
||||||
ud->get_semaphore().take_blocking();
|
ud->get_semaphore().take_blocking();
|
||||||
const float data = ud->get_roll(
|
const float data = ud->get_roll();
|
||||||
);
|
|
||||||
|
|
||||||
ud->get_semaphore().give();
|
ud->get_semaphore().give();
|
||||||
lua_pushnumber(L, data);
|
lua_pushnumber(L, data);
|
||||||
|
Loading…
Reference in New Issue
Block a user