Browse Source

AP_Scripting: rename AP_AHRS::get_position to get_location

gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
3438caebe2
  1. 2
      libraries/AP_Scripting/README.md
  2. 2
      libraries/AP_Scripting/docs/docs.lua
  3. 2
      libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua
  4. 2
      libraries/AP_Scripting/examples/ahrs-set-home-to-vehicle-location.lua
  5. 2
      libraries/AP_Scripting/examples/copter-fast-descent.lua
  6. 2
      libraries/AP_Scripting/examples/copter-fly-vertical-circle.lua
  7. 4
      libraries/AP_Scripting/examples/easter-egg.lua
  8. 2
      libraries/AP_Scripting/examples/fw_vtol_failsafe.lua
  9. 4
      libraries/AP_Scripting/examples/mission-edit-demo.lua
  10. 6
      libraries/AP_Scripting/examples/plane-wind-fs.lua
  11. 4
      libraries/AP_Scripting/examples/plane_aerobatics.lua
  12. 2
      libraries/AP_Scripting/examples/set-target-location.lua
  13. 4
      libraries/AP_Scripting/examples/set-target-velocity.lua
  14. 2
      libraries/AP_Scripting/examples/set_target_posvel_circle.lua
  15. 3
      libraries/AP_Scripting/generator/description/bindings.desc

2
libraries/AP_Scripting/README.md

@ -32,7 +32,7 @@ An example script is given below: @@ -32,7 +32,7 @@ An example script is given below:
```lua
function update () -- periodic function that will be called
current_pos = ahrs:get_position()
current_pos = ahrs:get_location()
home = ahrs:get_home()
if current_pos and home then
distance = current_pos:get_distance(ahrs:get_home()) -- calculate the distance from home

2
libraries/AP_Scripting/docs/docs.lua

@ -1880,7 +1880,7 @@ function ahrs:get_home() end @@ -1880,7 +1880,7 @@ function ahrs:get_home() end
-- desc
---@return Location_ud|nil
function ahrs:get_position() end
function ahrs:get_location() end
-- desc
---@return number

2
libraries/AP_Scripting/examples/SN-GCJA5-particle-sensor.lua

@ -160,7 +160,7 @@ function update() -- this is the loop which periodically runs @@ -160,7 +160,7 @@ function update() -- this is the loop which periodically runs
local alt = 0
-- try and get true position, but don't fail for no GPS lock
local position = ahrs:get_position()
local position = ahrs:get_location()
if position then
lat = position:lat()*10^-7
lng = position:lng()*10^-7

2
libraries/AP_Scripting/examples/ahrs-set-home-to-vehicle-location.lua

@ -4,7 +4,7 @@ @@ -4,7 +4,7 @@
function update ()
if ahrs:home_is_set() then
ahrs:set_home(ahrs:get_position())
ahrs:set_home(ahrs:get_location())
gcs:send_text(0, "Home position reset")
end

2
libraries/AP_Scripting/examples/copter-fast-descent.lua

@ -66,7 +66,7 @@ function update() @@ -66,7 +66,7 @@ function update()
if (stage == 0) then -- Stage0: initialise
local home = ahrs:get_home()
local curr_loc = ahrs:get_position()
local curr_loc = ahrs:get_location()
if home and curr_loc then
circle_center_pos = ahrs:get_relative_position_NED_origin()
circle_radius_rate_ms = 0 -- reset circle radius expandion rate to zero

2
libraries/AP_Scripting/examples/copter-fly-vertical-circle.lua

@ -38,7 +38,7 @@ function update() @@ -38,7 +38,7 @@ function update()
end
elseif (stage == 2) then -- Stage2: check if vehicle has reached target altitude
local home = ahrs:get_home()
local curr_loc = ahrs:get_position()
local curr_loc = ahrs:get_location()
if home and curr_loc then
local vec_from_home = home:get_distance_NED(curr_loc)
gcs:send_text(0, "alt above home: " .. tostring(math.floor(-vec_from_home:z())))

4
libraries/AP_Scripting/examples/easter-egg.lua

@ -26,7 +26,7 @@ function find_next_point () @@ -26,7 +26,7 @@ function find_next_point ()
target:lng(top_left:lng())
target:offset(math.random()*-100, math.random()*10)
gcs:send_text(6, string.format("New target %d %d", target:lat(), target:lng()))
local current = ahrs:get_position()
local current = ahrs:get_location()
if current then
last_distance = current:get_distance(target)
end
@ -35,7 +35,7 @@ function find_next_point () @@ -35,7 +35,7 @@ function find_next_point ()
end
function update ()
local current = ahrs:get_position()
local current = ahrs:get_location()
if current then
local dist = target:get_distance(current)
local now = millis()

2
libraries/AP_Scripting/examples/fw_vtol_failsafe.lua

@ -96,7 +96,7 @@ end @@ -96,7 +96,7 @@ end
-- check if we should switch to QLAND
function check_qland()
local target = vehicle:get_target_location()
local pos = ahrs:get_position()
local pos = ahrs:get_location()
if not target or not pos then
-- we can't estimate distance
return

4
libraries/AP_Scripting/examples/mission-edit-demo.lua

@ -7,7 +7,7 @@ demostage = 0 @@ -7,7 +7,7 @@ demostage = 0
eventcounter = 0
function update () -- periodic function that will be called
current_pos = ahrs:get_position()
current_pos = ahrs:get_location()
-- adds new/extra mission item at the end by copying the last one and modifying it
-- get number of last mission item
@ -257,7 +257,7 @@ function stage7 () @@ -257,7 +257,7 @@ function stage7 ()
end
function wait_for_home()
current_pos = ahrs:get_position()
current_pos = ahrs:get_location()
if current_pos == nil then
return wait_for_home, 1000
end

6
libraries/AP_Scripting/examples/plane-wind-fs.lua

@ -93,7 +93,7 @@ local timer_active = true @@ -93,7 +93,7 @@ local timer_active = true
-- otherwise returns the time in seconds to get back
local function time_to_home()
local home = ahrs:get_home()
local position = ahrs:get_position()
local position = ahrs:get_location()
local wind = ahrs:wind_estimate()
if home and position and wind then
@ -201,7 +201,7 @@ function track_return_time() @@ -201,7 +201,7 @@ function track_return_time()
end
local home = ahrs:get_home()
local position = ahrs:get_position()
local position = ahrs:get_location()
if home and position then
local now = millis()
@ -373,7 +373,7 @@ function update() @@ -373,7 +373,7 @@ function update()
-- Print the return distance
--[[local home = ahrs:get_home()
local position = ahrs:get_position()
local position = ahrs:get_location()
if home and position then
return_distance = position:get_distance(home)
end

4
libraries/AP_Scripting/examples/plane_aerobatics.lua

@ -161,7 +161,7 @@ local function height_controller(kP_param,kI_param,KnifeEdge_param,Imax) @@ -161,7 +161,7 @@ local function height_controller(kP_param,kI_param,KnifeEdge_param,Imax)
local PI = PI_controller(kP:get(), kI:get(), Imax)
function self.update(target)
local target_pitch = PI.update(initial_height, ahrs:get_position():alt()*0.01)
local target_pitch = PI.update(initial_height, ahrs:get_location():alt()*0.01)
local roll_rad = ahrs:get_roll()
local ke_add = math.abs(math.sin(roll_rad)) * KnifeEdge:get()
target_pitch = target_pitch + ke_add
@ -371,7 +371,7 @@ function update() @@ -371,7 +371,7 @@ function update()
running = false
last_id = id
initial_yaw_deg = math.deg(ahrs:get_yaw())
initial_height = ahrs:get_position():alt()*0.01
initial_height = ahrs:get_location():alt()*0.01
-- work out yaw between previous WP and next WP
local cnum = mission:get_current_nav_index()

2
libraries/AP_Scripting/examples/set-target-location.lua

@ -35,7 +35,7 @@ function update() @@ -35,7 +35,7 @@ function update()
-- change to land mode when within 2m of home
if not (mode == copter_land_mode_num) then
local home = ahrs:get_home()
local curr_loc = ahrs:get_position()
local curr_loc = ahrs:get_location()
if home and curr_loc then
local home_dist = curr_loc:get_distance(home) -- get horizontal distance to home
if (home_dist < wp_radius) then -- change to land mode if close

4
libraries/AP_Scripting/examples/set-target-velocity.lua

@ -31,7 +31,7 @@ function update() @@ -31,7 +31,7 @@ function update()
end
elseif (stage == 2) then -- Stage2: check if vehicle has reached target altitude
local home = ahrs:get_home()
local curr_loc = ahrs:get_position()
local curr_loc = ahrs:get_location()
if home and curr_loc then
local vec_from_home = home:get_distance_NED(curr_loc)
gcs:send_text(0, "alt above home: " .. tostring(math.floor(-vec_from_home:z())))
@ -41,7 +41,7 @@ function update() @@ -41,7 +41,7 @@ function update()
end
end
elseif (stage >= 3 and stage <= 6) then -- fly a square using velocity controller
local curr_loc = ahrs:get_position()
local curr_loc = ahrs:get_location()
local target_vel = Vector3f() -- create velocity vector
if (bottom_left_loc and curr_loc) then
local dist_NE = bottom_left_loc:get_distance_NE(curr_loc)

2
libraries/AP_Scripting/examples/set_target_posvel_circle.lua

@ -69,7 +69,7 @@ function update() @@ -69,7 +69,7 @@ function update()
end
else
-- calculate test starting location in NED
local cur_loc = ahrs:get_position()
local cur_loc = ahrs:get_location()
if cur_loc then
test_start_location = cur_loc.get_vector_from_origin_NEU(cur_loc)
if test_start_location then

3
libraries/AP_Scripting/generator/description/bindings.desc

@ -28,7 +28,8 @@ singleton AP_AHRS semaphore @@ -28,7 +28,8 @@ singleton AP_AHRS semaphore
singleton AP_AHRS method get_roll float
singleton AP_AHRS method get_pitch float
singleton AP_AHRS method get_yaw float
singleton AP_AHRS method get_position boolean Location'Null
singleton AP_AHRS method get_location boolean Location'Null
singleton AP_AHRS method get_location alias get_position
singleton AP_AHRS method get_home Location
singleton AP_AHRS method get_gyro Vector3f
singleton AP_AHRS method get_accel Vector3f

Loading…
Cancel
Save