diff --git a/libraries/AP_Scripting/generator/description/bindings.desc b/libraries/AP_Scripting/generator/description/bindings.desc index c6d3213760..07cfd86f12 100644 --- a/libraries/AP_Scripting/generator/description/bindings.desc +++ b/libraries/AP_Scripting/generator/description/bindings.desc @@ -16,6 +16,7 @@ userdata Location method get_vector_from_origin_NEU boolean Vector3f include AP_AHRS/AP_AHRS.h singleton AP_AHRS alias ahrs +singleton AP_AHRS semaphore singleton AP_AHRS method get_position boolean Location'Null singleton AP_AHRS method get_home Location singleton AP_AHRS method get_gyro Vector3f diff --git a/libraries/AP_Scripting/generator/src/main.c b/libraries/AP_Scripting/generator/src/main.c index d27f1fd0e2..309886ab81 100644 --- a/libraries/AP_Scripting/generator/src/main.c +++ b/libraries/AP_Scripting/generator/src/main.c @@ -14,6 +14,7 @@ char keyword_include[] = "include"; char keyword_method[] = "method"; char keyword_operator[] = "operator"; char keyword_read[] = "read"; +char keyword_semaphore[] = "semaphore"; char keyword_singleton[] = "singleton"; char keyword_userdata[] = "userdata"; char keyword_write[] = "write"; @@ -278,6 +279,10 @@ struct userdata_field { unsigned int access_flags; }; +enum userdata_flags { + UD_FLAG_SEMAPHORE = (1U << 0), +}; + struct userdata { struct userdata * next; char *name; // name of the C++ singleton @@ -286,6 +291,7 @@ struct userdata { struct method *methods; enum userdata_type ud_type; uint32_t operations; // bitset of enum operation_types + int flags; // flags from the userdata_flags enum }; static struct userdata *parsed_userdata = NULL; @@ -688,17 +694,18 @@ void handle_singleton(void) { node->alias = (char *)allocate(strlen(alias) + 1); strcpy(node->alias, alias); - // ensure no more tokens on the line - if (next_token()) { - error(ERROR_HEADER, "Singleton contained an unexpected extra token: %s", state.token); - } - return; + } else if (strcmp(type, keyword_semaphore) == 0) { + node->flags |= UD_FLAG_SEMAPHORE; } else if (strcmp(type, keyword_method) == 0) { handle_method(node->name, &(node->methods)); } else { - error(ERROR_SINGLETON, "Singletons only support methods or aliases (got %s)", type); + error(ERROR_SINGLETON, "Singletons only support aliases, methods or semaphore keyowrds (got %s)", type); } + // ensure no more tokens on the line + if (next_token()) { + error(ERROR_HEADER, "Singleton contained an unexpected extra token: %s", state.token); + } } void sanity_check_userdata(void) { @@ -1038,6 +1045,10 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth arg_count++; } + if (data->flags & UD_FLAG_SEMAPHORE) { + fprintf(source, " ud->get_semaphore().take_blocking();\n"); + } + switch (method->return_type.type) { case TYPE_BOOLEAN: fprintf(source, " const bool data = ud->%s(\n", method->name); @@ -1084,8 +1095,11 @@ void emit_userdata_method(const struct userdata *data, const struct method *meth } arg_count++; } - fprintf(source, ");\n\n"); + fprintf(source, "%s);\n\n", arg_count == 2 ? " " : ""); + if (data->flags & UD_FLAG_SEMAPHORE) { + fprintf(source, " ud->get_semaphore().give();\n"); + } int return_count = 1; // number of arguments to return switch (method->return_type.type) { diff --git a/libraries/AP_Scripting/lua_generated_bindings.cpp b/libraries/AP_Scripting/lua_generated_bindings.cpp index d93c4f8ec2..1499e8ae3e 100644 --- a/libraries/AP_Scripting/lua_generated_bindings.cpp +++ b/libraries/AP_Scripting/lua_generated_bindings.cpp @@ -257,7 +257,7 @@ static int Vector2f_is_zero(lua_State *L) { Vector2f * ud = check_Vector2f(L, 1); ud->is_zero( -); + ); return 0; } @@ -272,7 +272,7 @@ static int Vector2f_is_inf(lua_State *L) { Vector2f * ud = check_Vector2f(L, 1); ud->is_inf( -); + ); return 0; } @@ -287,7 +287,7 @@ static int Vector2f_is_nan(lua_State *L) { Vector2f * ud = check_Vector2f(L, 1); ud->is_nan( -); + ); return 0; } @@ -302,7 +302,7 @@ static int Vector2f_normalize(lua_State *L) { Vector2f * ud = check_Vector2f(L, 1); ud->normalize( -); + ); return 0; } @@ -317,7 +317,7 @@ static int Vector2f_length(lua_State *L) { Vector2f * ud = check_Vector2f(L, 1); const float data = ud->length( -); + ); lua_pushnumber(L, data); return 1; @@ -363,7 +363,7 @@ static int Vector3f_is_zero(lua_State *L) { Vector3f * ud = check_Vector3f(L, 1); ud->is_zero( -); + ); return 0; } @@ -378,7 +378,7 @@ static int Vector3f_is_inf(lua_State *L) { Vector3f * ud = check_Vector3f(L, 1); ud->is_inf( -); + ); return 0; } @@ -393,7 +393,7 @@ static int Vector3f_is_nan(lua_State *L) { Vector3f * ud = check_Vector3f(L, 1); ud->is_nan( -); + ); return 0; } @@ -408,7 +408,7 @@ static int Vector3f_normalize(lua_State *L) { Vector3f * ud = check_Vector3f(L, 1); ud->normalize( -); + ); return 0; } @@ -423,7 +423,7 @@ static int Vector3f_length(lua_State *L) { Vector3f * ud = check_Vector3f(L, 1); const float data = ud->length( -); + ); lua_pushnumber(L, data); return 1; @@ -560,7 +560,7 @@ const luaL_Reg Location_meta[] = { }; static int AP_Relay_toggle(lua_State *L) { - // 1 uint8_t 121 : 8 + // 1 uint8_t 122 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -583,7 +583,7 @@ static int AP_Relay_toggle(lua_State *L) { } static int AP_Relay_enabled(lua_State *L) { - // 1 uint8_t 120 : 8 + // 1 uint8_t 121 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -607,7 +607,7 @@ static int AP_Relay_enabled(lua_State *L) { } static int AP_Relay_off(lua_State *L) { - // 1 uint8_t 119 : 8 + // 1 uint8_t 120 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -630,7 +630,7 @@ static int AP_Relay_off(lua_State *L) { } static int AP_Relay_on(lua_State *L) { - // 1 uint8_t 118 : 8 + // 1 uint8_t 119 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -653,8 +653,8 @@ static int AP_Relay_on(lua_State *L) { } static int AP_Terrain_height_above_terrain(lua_State *L) { - // 1 float 113 : 6 - // 2 bool 113 : 7 + // 1 float 114 : 6 + // 2 bool 114 : 7 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -682,9 +682,9 @@ static int AP_Terrain_height_above_terrain(lua_State *L) { } static int AP_Terrain_height_relative_home_equivalent(lua_State *L) { - // 1 float 112 : 8 - // 2 float 112 : 9 - // 3 bool 112 : 10 + // 1 float 113 : 8 + // 2 float 113 : 9 + // 3 bool 113 : 10 const int args = lua_gettop(L); if (args > 3) { return luaL_argerror(L, args, "too many arguments"); @@ -716,8 +716,8 @@ static int AP_Terrain_height_relative_home_equivalent(lua_State *L) { } static int AP_Terrain_height_terrain_difference_home(lua_State *L) { - // 1 float 111 : 6 - // 2 bool 111 : 7 + // 1 float 112 : 6 + // 2 bool 112 : 7 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -745,9 +745,9 @@ static int AP_Terrain_height_terrain_difference_home(lua_State *L) { } static int AP_Terrain_height_amsl(lua_State *L) { - // 1 Location 110 : 6 - // 2 float 110 : 7 - // 3 bool 110 : 8 + // 1 Location 111 : 6 + // 2 float 111 : 7 + // 3 bool 111 : 8 const int args = lua_gettop(L); if (args > 3) { return luaL_argerror(L, args, "too many arguments"); @@ -790,7 +790,7 @@ static int AP_Terrain_status(lua_State *L) { } const uint8_t data = ud->status( -); + ); lua_pushinteger(L, data); return 1; @@ -810,7 +810,7 @@ static int AP_Terrain_enabled(lua_State *L) { } const bool data = ud->enabled( -); + ); lua_pushboolean(L, data); return 1; @@ -830,14 +830,14 @@ static int RangeFinder_num_sensors(lua_State *L) { } const uint8_t data = ud->num_sensors( -); + ); lua_pushinteger(L, data); return 1; } static int AP_Notify_play_tune(lua_State *L) { - // 1 userdata 98 : 6 + // 1 userdata 99 : 6 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -871,7 +871,7 @@ static int AP_GPS_first_unconfigured_gps(lua_State *L) { } const uint8_t data = ud->first_unconfigured_gps( -); + ); lua_pushinteger(L, data); return 1; @@ -891,14 +891,14 @@ static int AP_GPS_all_configured(lua_State *L) { } const bool data = ud->all_configured( -); + ); lua_pushboolean(L, data); return 1; } static int AP_GPS_get_antenna_offset(lua_State *L) { - // 1 uint8_t 69 : 8 + // 1 uint8_t 70 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -923,7 +923,7 @@ static int AP_GPS_get_antenna_offset(lua_State *L) { } static int AP_GPS_have_vertical_velocity(lua_State *L) { - // 1 uint8_t 68 : 8 + // 1 uint8_t 69 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -947,7 +947,7 @@ static int AP_GPS_have_vertical_velocity(lua_State *L) { } static int AP_GPS_last_message_time_ms(lua_State *L) { - // 1 uint8_t 67 : 8 + // 1 uint8_t 68 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -972,7 +972,7 @@ static int AP_GPS_last_message_time_ms(lua_State *L) { } static int AP_GPS_last_fix_time_ms(lua_State *L) { - // 1 uint8_t 66 : 8 + // 1 uint8_t 67 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -997,7 +997,7 @@ static int AP_GPS_last_fix_time_ms(lua_State *L) { } static int AP_GPS_get_vdop(lua_State *L) { - // 1 uint8_t 65 : 8 + // 1 uint8_t 66 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1021,7 +1021,7 @@ static int AP_GPS_get_vdop(lua_State *L) { } static int AP_GPS_get_hdop(lua_State *L) { - // 1 uint8_t 64 : 8 + // 1 uint8_t 65 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1045,7 +1045,7 @@ static int AP_GPS_get_hdop(lua_State *L) { } static int AP_GPS_time_week_ms(lua_State *L) { - // 1 uint8_t 63 : 8 + // 1 uint8_t 64 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1070,7 +1070,7 @@ static int AP_GPS_time_week_ms(lua_State *L) { } static int AP_GPS_time_week(lua_State *L) { - // 1 uint8_t 62 : 8 + // 1 uint8_t 63 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1094,7 +1094,7 @@ static int AP_GPS_time_week(lua_State *L) { } static int AP_GPS_num_sats(lua_State *L) { - // 1 uint8_t 61 : 8 + // 1 uint8_t 62 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1118,7 +1118,7 @@ static int AP_GPS_num_sats(lua_State *L) { } static int AP_GPS_ground_course(lua_State *L) { - // 1 uint8_t 60 : 8 + // 1 uint8_t 61 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1142,7 +1142,7 @@ static int AP_GPS_ground_course(lua_State *L) { } static int AP_GPS_ground_speed(lua_State *L) { - // 1 uint8_t 59 : 8 + // 1 uint8_t 60 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1166,7 +1166,7 @@ static int AP_GPS_ground_speed(lua_State *L) { } static int AP_GPS_velocity(lua_State *L) { - // 1 uint8_t 58 : 8 + // 1 uint8_t 59 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1191,8 +1191,8 @@ static int AP_GPS_velocity(lua_State *L) { } static int AP_GPS_vertical_accuracy(lua_State *L) { - // 1 uint8_t 57 : 8 - // 2 float 57 : 9 + // 1 uint8_t 58 : 8 + // 2 float 58 : 9 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1222,8 +1222,8 @@ static int AP_GPS_vertical_accuracy(lua_State *L) { } static int AP_GPS_horizontal_accuracy(lua_State *L) { - // 1 uint8_t 56 : 8 - // 2 float 56 : 9 + // 1 uint8_t 57 : 8 + // 2 float 57 : 9 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1253,8 +1253,8 @@ static int AP_GPS_horizontal_accuracy(lua_State *L) { } static int AP_GPS_speed_accuracy(lua_State *L) { - // 1 uint8_t 55 : 8 - // 2 float 55 : 9 + // 1 uint8_t 56 : 8 + // 2 float 56 : 9 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1284,7 +1284,7 @@ static int AP_GPS_speed_accuracy(lua_State *L) { } static int AP_GPS_location(lua_State *L) { - // 1 uint8_t 54 : 8 + // 1 uint8_t 55 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1309,7 +1309,7 @@ static int AP_GPS_location(lua_State *L) { } static int AP_GPS_status(lua_State *L) { - // 1 uint8_t 53 : 8 + // 1 uint8_t 54 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1346,7 +1346,7 @@ static int AP_GPS_primary_sensor(lua_State *L) { } const uint8_t data = ud->primary_sensor( -); + ); lua_pushinteger(L, data); return 1; @@ -1366,15 +1366,15 @@ static int AP_GPS_num_sensors(lua_State *L) { } const uint8_t data = ud->num_sensors( -); + ); lua_pushinteger(L, data); return 1; } static int AP_BattMonitor_get_temperature(lua_State *L) { - // 1 float 46 : 6 - // 2 uint8_t 46 : 9 + // 1 float 47 : 6 + // 2 uint8_t 47 : 9 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1404,7 +1404,7 @@ static int AP_BattMonitor_get_temperature(lua_State *L) { } static int AP_BattMonitor_overpower_detected(lua_State *L) { - // 1 uint8_t 45 : 8 + // 1 uint8_t 46 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1441,14 +1441,14 @@ static int AP_BattMonitor_has_failsafed(lua_State *L) { } const bool data = ud->has_failsafed( -); + ); lua_pushboolean(L, data); return 1; } static int AP_BattMonitor_pack_capacity_mah(lua_State *L) { - // 1 uint8_t 43 : 8 + // 1 uint8_t 44 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1472,7 +1472,7 @@ static int AP_BattMonitor_pack_capacity_mah(lua_State *L) { } static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) { - // 1 uint8_t 42 : 8 + // 1 uint8_t 43 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1496,7 +1496,7 @@ static int AP_BattMonitor_capacity_remaining_pct(lua_State *L) { } static int AP_BattMonitor_consumed_wh(lua_State *L) { - // 1 uint8_t 41 : 8 + // 1 uint8_t 42 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1520,7 +1520,7 @@ static int AP_BattMonitor_consumed_wh(lua_State *L) { } static int AP_BattMonitor_consumed_mah(lua_State *L) { - // 1 uint8_t 40 : 8 + // 1 uint8_t 41 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1544,7 +1544,7 @@ static int AP_BattMonitor_consumed_mah(lua_State *L) { } static int AP_BattMonitor_current_amps(lua_State *L) { - // 1 uint8_t 39 : 8 + // 1 uint8_t 40 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1568,7 +1568,7 @@ static int AP_BattMonitor_current_amps(lua_State *L) { } static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) { - // 1 uint8_t 38 : 8 + // 1 uint8_t 39 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1592,7 +1592,7 @@ static int AP_BattMonitor_voltage_resting_estimate(lua_State *L) { } static int AP_BattMonitor_voltage(lua_State *L) { - // 1 uint8_t 37 : 8 + // 1 uint8_t 38 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1616,7 +1616,7 @@ static int AP_BattMonitor_voltage(lua_State *L) { } static int AP_BattMonitor_has_current(lua_State *L) { - // 1 uint8_t 36 : 8 + // 1 uint8_t 37 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1640,7 +1640,7 @@ static int AP_BattMonitor_has_current(lua_State *L) { } static int AP_BattMonitor_has_consumed_energy(lua_State *L) { - // 1 uint8_t 35 : 8 + // 1 uint8_t 36 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1664,7 +1664,7 @@ static int AP_BattMonitor_has_consumed_energy(lua_State *L) { } static int AP_BattMonitor_healthy(lua_State *L) { - // 1 uint8_t 34 : 8 + // 1 uint8_t 35 : 8 const int args = lua_gettop(L); if (args > 2) { return luaL_argerror(L, args, "too many arguments"); @@ -1701,7 +1701,7 @@ static int AP_BattMonitor_num_instances(lua_State *L) { } const uint8_t data = ud->num_instances( -); + ); lua_pushinteger(L, data); return 1; @@ -1720,9 +1720,11 @@ static int AP_AHRS_prearm_healthy(lua_State *L) { return luaL_argerror(L, args, "ahrs not supported on this firmware"); } + ud->get_semaphore().take_blocking(); const bool data = ud->prearm_healthy( -); + ); + ud->get_semaphore().give(); lua_pushboolean(L, data); return 1; } @@ -1740,15 +1742,17 @@ static int AP_AHRS_home_is_set(lua_State *L) { return luaL_argerror(L, args, "ahrs not supported on this firmware"); } + ud->get_semaphore().take_blocking(); const bool data = ud->home_is_set( -); + ); + ud->get_semaphore().give(); lua_pushboolean(L, data); return 1; } static int AP_AHRS_get_relative_position_NED_home(lua_State *L) { - // 1 Vector3f 26 : 6 + // 1 Vector3f 27 : 6 const int args = lua_gettop(L); if (args > 1) { return luaL_argerror(L, args, "too many arguments"); @@ -1762,9 +1766,11 @@ static int AP_AHRS_get_relative_position_NED_home(lua_State *L) { } Vector3f data_5002 = {}; + ud->get_semaphore().take_blocking(); const bool data = ud->get_relative_position_NED_home( data_5002); + ud->get_semaphore().give(); if (data) { new_Vector3f(L); *check_Vector3f(L, -1) = data_5002; @@ -1775,7 +1781,7 @@ static int AP_AHRS_get_relative_position_NED_home(lua_State *L) { } static int AP_AHRS_get_velocity_NED(lua_State *L) { - // 1 Vector3f 25 : 6 + // 1 Vector3f 26 : 6 const int args = lua_gettop(L); if (args > 1) { return luaL_argerror(L, args, "too many arguments"); @@ -1789,9 +1795,11 @@ static int AP_AHRS_get_velocity_NED(lua_State *L) { } Vector3f data_5002 = {}; + ud->get_semaphore().take_blocking(); const bool data = ud->get_velocity_NED( data_5002); + ud->get_semaphore().give(); if (data) { new_Vector3f(L); *check_Vector3f(L, -1) = data_5002; @@ -1814,9 +1822,11 @@ static int AP_AHRS_groundspeed_vector(lua_State *L) { return luaL_argerror(L, args, "ahrs not supported on this firmware"); } + ud->get_semaphore().take_blocking(); const Vector2f &data = ud->groundspeed_vector( -); + ); + ud->get_semaphore().give(); new_Vector2f(L); *check_Vector2f(L, -1) = data; return 1; @@ -1835,16 +1845,18 @@ static int AP_AHRS_wind_estimate(lua_State *L) { return luaL_argerror(L, args, "ahrs not supported on this firmware"); } + ud->get_semaphore().take_blocking(); const Vector3f &data = ud->wind_estimate( -); + ); + ud->get_semaphore().give(); new_Vector3f(L); *check_Vector3f(L, -1) = data; return 1; } static int AP_AHRS_get_hagl(lua_State *L) { - // 1 float 22 : 6 + // 1 float 23 : 6 const int args = lua_gettop(L); if (args > 1) { return luaL_argerror(L, args, "too many arguments"); @@ -1858,9 +1870,11 @@ static int AP_AHRS_get_hagl(lua_State *L) { } float data_5002 = {}; + ud->get_semaphore().take_blocking(); const bool data = ud->get_hagl( data_5002); + ud->get_semaphore().give(); if (data) { lua_pushnumber(L, data_5002); } else { @@ -1882,9 +1896,11 @@ static int AP_AHRS_get_gyro(lua_State *L) { return luaL_argerror(L, args, "ahrs not supported on this firmware"); } + ud->get_semaphore().take_blocking(); const Vector3f &data = ud->get_gyro( -); + ); + ud->get_semaphore().give(); new_Vector3f(L); *check_Vector3f(L, -1) = data; return 1; @@ -1903,16 +1919,18 @@ static int AP_AHRS_get_home(lua_State *L) { return luaL_argerror(L, args, "ahrs not supported on this firmware"); } + ud->get_semaphore().take_blocking(); const Location &data = ud->get_home( -); + ); + ud->get_semaphore().give(); new_Location(L); *check_Location(L, -1) = data; return 1; } static int AP_AHRS_get_position(lua_State *L) { - // 1 Location 19 : 6 + // 1 Location 20 : 6 const int args = lua_gettop(L); if (args > 1) { return luaL_argerror(L, args, "too many arguments"); @@ -1926,9 +1944,11 @@ static int AP_AHRS_get_position(lua_State *L) { } Location data_5002 = {}; + ud->get_semaphore().take_blocking(); const bool data = ud->get_position( data_5002); + ud->get_semaphore().give(); if (data) { new_Location(L); *check_Location(L, -1) = data_5002;