mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AP_Scripting: add get_origin and set_home bindings
added bindings and example scripts for set_home and get_origin
This commit is contained in:
parent
d82a229584
commit
a617175881
@ -0,0 +1,21 @@
|
|||||||
|
-- example script for using "get_origin()"
|
||||||
|
-- prints the home and ekf origin lat long and altitude to the console every 5 seconds
|
||||||
|
|
||||||
|
function update ()
|
||||||
|
|
||||||
|
home = ahrs:get_home()
|
||||||
|
origin = ahrs:get_origin()
|
||||||
|
|
||||||
|
if home then
|
||||||
|
gcs:send_text(0, string.format("Home - Lat:%.1f Long:%.1f Alt:%.1f", home:lat(), home:lng(), home:alt()))
|
||||||
|
end
|
||||||
|
|
||||||
|
if origin then
|
||||||
|
gcs:send_text(0, string.format("Origin - Lat:%.1f Long:%.1f Alt:%.1f", origin:lat(), origin:lng(), origin:alt()))
|
||||||
|
end
|
||||||
|
|
||||||
|
return update, 5000
|
||||||
|
|
||||||
|
end
|
||||||
|
|
||||||
|
return update()
|
@ -0,0 +1,15 @@
|
|||||||
|
-- example script for using "set_home()"
|
||||||
|
-- sets the home location to the current vehicle location every 5 seconds
|
||||||
|
|
||||||
|
function update ()
|
||||||
|
|
||||||
|
if ahrs:home_is_set() then
|
||||||
|
ahrs:set_home(ahrs:get_position())
|
||||||
|
gcs:send_text(0, "Home position reset")
|
||||||
|
end
|
||||||
|
|
||||||
|
return update, 5000
|
||||||
|
|
||||||
|
end
|
||||||
|
|
||||||
|
return update()
|
@ -44,6 +44,8 @@ singleton AP_AHRS method get_EAS2TAS float
|
|||||||
singleton AP_AHRS method get_variances boolean float'Null float'Null float'Null Vector3f'Null float'Null
|
singleton AP_AHRS method get_variances boolean float'Null float'Null float'Null Vector3f'Null float'Null
|
||||||
singleton AP_AHRS method set_posvelyaw_source_set void uint8_t 0 2
|
singleton AP_AHRS method set_posvelyaw_source_set void uint8_t 0 2
|
||||||
singleton AP_AHRS method get_vel_innovations_and_variances_for_source boolean uint8_t 3 6 Vector3f'Null Vector3f'Null
|
singleton AP_AHRS method get_vel_innovations_and_variances_for_source boolean uint8_t 3 6 Vector3f'Null Vector3f'Null
|
||||||
|
singleton AP_AHRS method set_home boolean Location
|
||||||
|
singleton AP_AHRS method get_origin boolean Location'Null
|
||||||
|
|
||||||
include AP_Arming/AP_Arming.h
|
include AP_Arming/AP_Arming.h
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user