From 29d05dfeac8dc8de593431a796c936474d2f0b9e Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 5 Apr 2019 13:51:24 +0900 Subject: [PATCH] Copter: loiter mode gets roll and pitch from loiter_nav both wp_nav and loiter_nav's get_roll() and get_pitch() simply get their values from the same underlying position controller --- ArduCopter/mode_loiter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_loiter.cpp b/ArduCopter/mode_loiter.cpp index e575e586d1..7a679a6622 100644 --- a/ArduCopter/mode_loiter.cpp +++ b/ArduCopter/mode_loiter.cpp @@ -122,7 +122,7 @@ void Copter::ModeLoiter::run() attitude_control->set_yaw_target_to_current_heading(); pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero loiter_nav->init_target(); - attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate); + attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate); pos_control->update_z_controller(); break;