mirror of https://github.com/ArduPilot/ardupilot
Copter: Guided: move to zero velocity after takeoff
This commit is contained in:
parent
0ad493fdf7
commit
f5a15dd85b
|
@ -513,9 +513,8 @@ void ModeGuided::takeoff_run()
|
||||||
copter.landinggear.retract_after_takeoff();
|
copter.landinggear.retract_after_takeoff();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// switch to position control mode but maintain current target
|
// change to velocity control after take off.
|
||||||
const Vector3f target = pos_control->get_pos_target_cm().tofloat();
|
init(true);
|
||||||
set_destination(target, false, 0, false, 0, false, wp_nav->origin_and_destination_are_terrain_alt());
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue