From 7a94274faf1cf3e64ffcb2c7ade655d050355864 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 13 Sep 2024 13:17:55 +0900 Subject: [PATCH] AP_Scripting: copter-posoffset uses pos-vel-accel offset targets --- libraries/AP_Scripting/examples/copter-posoffset.lua | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Scripting/examples/copter-posoffset.lua b/libraries/AP_Scripting/examples/copter-posoffset.lua index d8fcda562e8c5f..1f40fcb16e8613 100644 --- a/libraries/AP_Scripting/examples/copter-posoffset.lua +++ b/libraries/AP_Scripting/examples/copter-posoffset.lua @@ -82,7 +82,7 @@ function update() local pos_offset_NED = Vector3f() pos_offset_NED:x(PSC_OFS_POS_N:get()) pos_offset_NED:y(PSC_OFS_POS_E:get()) - if not vehicle:set_pos_offset(pos_offset_NED) then + if not vehicle:set_posvelaccel_offset(pos_offset_NED, Vector3f(), Vector3f()) then gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: failed to set pos offset") end test_position = not pos_offsets_zero @@ -91,7 +91,7 @@ function update() local vel_offset_NED = Vector3f() vel_offset_NED:x(PSC_OFS_VEL_N:get()) vel_offset_NED:y(PSC_OFS_VEL_E:get()) - if not vehicle:set_vel_offset(vel_offset_NED) then + if not vehicle:set_velaccel_offset(vel_offset_NED, Vector3f()) then gcs:send_text(MAV_SEVERITY.ERROR, "copter-posoffset: failed to set vel offset") end end