From 0d23c3b910b4b7290d5ec2899092874b97b47097 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 17 Mar 2014 10:17:57 +0900 Subject: [PATCH] Copter: initialise vertical speed for Loiter mode --- ArduCopter/control_loiter.pde | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduCopter/control_loiter.pde b/ArduCopter/control_loiter.pde index 251163393f..01fe79fc58 100644 --- a/ArduCopter/control_loiter.pde +++ b/ArduCopter/control_loiter.pde @@ -8,10 +8,16 @@ static bool loiter_init(bool ignore_checks) { if (GPS_ok() || ignore_checks) { + // set target to current position wp_nav.init_loiter_target(); + + // initialize vertical speeds + pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max); + // initialise altitude target to stopping point pos_control.set_target_to_stopping_point_z(); + return true; }else{ return false;