Copter: switch to pos control when takeoff finish

This commit is contained in:
Pierre Kancir 2018-07-25 19:17:23 +02:00 committed by Peter Barker
parent 20c1c4c684
commit 84ff9c6928
2 changed files with 8 additions and 0 deletions

View File

@ -729,6 +729,10 @@ bool Copter::ModeAuto::verify_command(const AP_Mission::Mission_Command& cmd)
void Copter::ModeAuto::takeoff_run() void Copter::ModeAuto::takeoff_run()
{ {
auto_takeoff_run(); auto_takeoff_run();
if (wp_nav->reached_wp_destination()) {
const Vector3f target = wp_nav->get_wp_destination();
wp_start(target);
}
} }
// auto_wp_run - runs the auto waypoint controller // auto_wp_run - runs the auto waypoint controller

View File

@ -366,6 +366,10 @@ void Copter::ModeGuided::run()
void Copter::ModeGuided::takeoff_run() void Copter::ModeGuided::takeoff_run()
{ {
auto_takeoff_run(); auto_takeoff_run();
if (wp_nav->reached_wp_destination()) {
const Vector3f target = wp_nav->get_wp_destination();
set_destination(target);
}
} }
void Copter::Mode::auto_takeoff_run() void Copter::Mode::auto_takeoff_run()