Scripting: added Lat,Lon to aerobatics POSM/POST

this makes "map POSM POST" work on aerobatic scripts
This commit is contained in:
Andrew Tridgell 2024-09-26 10:56:24 +10:00
parent 00163ce988
commit 88957235d2
1 changed files with 6 additions and 2 deletions

View File

@ -2124,7 +2124,9 @@ end
-- log a pose from position and quaternion attitude
function log_pose(logname, pos, quat)
logger.write(logname, 'px,py,pz,q1,q2,q3,q4,r,p,y', 'ffffffffff',
local loc = ahrs:get_origin():copy()
loc:offset(pos:x(),pos:y())
logger.write(logname, 'px,py,pz,q1,q2,q3,q4,r,p,y,Lat,Lon', 'ffffffffffLL',
pos:x(),
pos:y(),
pos:z(),
@ -2134,7 +2136,9 @@ function log_pose(logname, pos, quat)
quat:q4(),
math.deg(quat:get_euler_roll()),
math.deg(quat:get_euler_pitch()),
math.deg(quat:get_euler_yaw()))
math.deg(quat:get_euler_yaw()),
loc:lat(),
loc:lng())
end
--[[