mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Scripting: replace location_offset() and get_distance() function calls with Location object member function calls
This allows removing duplicated code
This commit is contained in:
parent
00a80f3a1a
commit
67bbc6962a
@ -219,8 +219,7 @@ static int location_distance(lua_State *L) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
}
|
||||
|
||||
lua_pushnumber(L, get_distance(*check_location(L, -2),
|
||||
*check_location(L, -1)));
|
||||
lua_pushnumber(L, *check_location(L, -2).get_distance(*check_location(L, -1)));
|
||||
|
||||
return 1;
|
||||
}
|
||||
@ -272,7 +271,7 @@ static int location_offset(lua_State *L) {
|
||||
return luaL_argerror(L, args, "too many arguments");
|
||||
}
|
||||
|
||||
location_offset(*check_location(L, -3),
|
||||
*check_location(L, -3).offset(
|
||||
luaL_checknumber(L, -2),
|
||||
luaL_checknumber(L, -1));
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user