mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Scripting: Fix bad return types on is_nan, is_inf, is_zero
This commit is contained in:
parent
9e04939adf
commit
852f85ec10
@ -87,9 +87,9 @@ userdata Vector3f field y float read write -FLT_MAX FLT_MAX
|
|||||||
userdata Vector3f field z float read write -FLT_MAX FLT_MAX
|
userdata Vector3f field z float read write -FLT_MAX FLT_MAX
|
||||||
userdata Vector3f method length float
|
userdata Vector3f method length float
|
||||||
userdata Vector3f method normalize void
|
userdata Vector3f method normalize void
|
||||||
userdata Vector3f method is_nan void
|
userdata Vector3f method is_nan boolean
|
||||||
userdata Vector3f method is_inf void
|
userdata Vector3f method is_inf boolean
|
||||||
userdata Vector3f method is_zero void
|
userdata Vector3f method is_zero boolean
|
||||||
userdata Vector3f operator +
|
userdata Vector3f operator +
|
||||||
userdata Vector3f operator -
|
userdata Vector3f operator -
|
||||||
|
|
||||||
@ -97,9 +97,9 @@ userdata Vector2f field x float read write -FLT_MAX FLT_MAX
|
|||||||
userdata Vector2f field y float read write -FLT_MAX FLT_MAX
|
userdata Vector2f field y float read write -FLT_MAX FLT_MAX
|
||||||
userdata Vector2f method length float
|
userdata Vector2f method length float
|
||||||
userdata Vector2f method normalize void
|
userdata Vector2f method normalize void
|
||||||
userdata Vector2f method is_nan void
|
userdata Vector2f method is_nan boolean
|
||||||
userdata Vector2f method is_inf void
|
userdata Vector2f method is_inf boolean
|
||||||
userdata Vector2f method is_zero void
|
userdata Vector2f method is_zero boolean
|
||||||
userdata Vector2f operator +
|
userdata Vector2f operator +
|
||||||
userdata Vector2f operator -
|
userdata Vector2f operator -
|
||||||
|
|
||||||
|
@ -262,25 +262,28 @@ 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();
|
const bool data = ud->is_zero();
|
||||||
|
|
||||||
return 0;
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
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();
|
const bool data = ud->is_inf();
|
||||||
|
|
||||||
return 0;
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
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();
|
const bool data = ud->is_nan();
|
||||||
|
|
||||||
return 0;
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
static int Vector2f_normalize(lua_State *L) {
|
static int Vector2f_normalize(lua_State *L) {
|
||||||
@ -321,25 +324,28 @@ 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();
|
const bool data = ud->is_zero();
|
||||||
|
|
||||||
return 0;
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
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();
|
const bool data = ud->is_inf();
|
||||||
|
|
||||||
return 0;
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
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();
|
const bool data = ud->is_nan();
|
||||||
|
|
||||||
return 0;
|
lua_pushboolean(L, data);
|
||||||
|
return 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
static int Vector3f_normalize(lua_State *L) {
|
static int Vector3f_normalize(lua_State *L) {
|
||||||
|
Loading…
Reference in New Issue
Block a user