From 1c59ec8b9424becee0d91175c62336678f12b4aa Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Thu, 3 Oct 2024 10:25:03 +0930 Subject: [PATCH] Copter: PosHold supports offsets --- ArduCopter/mode_poshold.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_poshold.cpp b/ArduCopter/mode_poshold.cpp index bf514c61cd..c06072c597 100644 --- a/ArduCopter/mode_poshold.cpp +++ b/ArduCopter/mode_poshold.cpp @@ -377,7 +377,7 @@ void ModePosHold::run() pitch_mode = RPMode::BRAKE_TO_LOITER; brake.to_loiter_timer = POSHOLD_BRAKE_TO_LOITER_TIMER; // init loiter controller - loiter_nav->init_target(inertial_nav.get_position_xy_cm()); + loiter_nav->init_target(inertial_nav.get_position_xy_cm() - pos_control->get_pos_offset_cm().xy().tofloat()); // set delay to start of wind compensation estimate updates wind_comp_start_timer = POSHOLD_WIND_COMP_START_TIMER; }