Copter: rtl passes speed to wpnav::init

This commit is contained in:
Randy Mackay 2020-10-08 12:45:40 +09:00
parent 9d91b6c3be
commit 7c14f4de0d

View File

@ -18,7 +18,7 @@ bool ModeRTL::init(bool ignore_checks)
}
}
// initialise waypoint and spline controller
wp_nav->wp_and_spline_init();
wp_nav->wp_and_spline_init(g.rtl_speed_cms);
_state = RTL_Starting;
_state_complete = true; // see run() method below
terrain_following_allowed = !copter.failsafe.terrain;
@ -117,11 +117,6 @@ void ModeRTL::climb_start()
_state = RTL_InitialClimb;
_state_complete = false;
// RTL_SPEED == 0 means use WPNAV_SPEED
if (g.rtl_speed_cms != 0) {
wp_nav->set_speed_xy(g.rtl_speed_cms);
}
// set the destination
if (!wp_nav->set_wp_destination_loc(rtl_path.climb_target) || !wp_nav->set_wp_destination_next_loc(rtl_path.return_target)) {
// this should not happen because rtl_build_path will have checked terrain data was available