mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: switch to pos control when takeoff finish
This commit is contained in:
parent
20c1c4c684
commit
84ff9c6928
@ -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
|
||||||
|
@ -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()
|
||||||
|
Loading…
Reference in New Issue
Block a user