mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
Copter: fix takeoff drift if vehicle is not in origin
This commit is contained in:
parent
9b88823ce6
commit
7b60ace18b
@ -146,7 +146,7 @@ void Mode::auto_takeoff_run()
|
|||||||
// if not armed set throttle to zero and exit immediately
|
// if not armed set throttle to zero and exit immediately
|
||||||
if (!motors->armed() || !copter.ap.auto_armed) {
|
if (!motors->armed() || !copter.ap.auto_armed) {
|
||||||
make_safe_spool_down();
|
make_safe_spool_down();
|
||||||
wp_nav->shift_wp_origin_to_current_pos();
|
wp_nav->shift_wp_origin_and_destination_to_current_pos_xy();
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -165,7 +165,7 @@ void Mode::auto_takeoff_run()
|
|||||||
set_land_complete(false);
|
set_land_complete(false);
|
||||||
} else {
|
} else {
|
||||||
// motors have not completed spool up yet so relax navigation and position controllers
|
// motors have not completed spool up yet so relax navigation and position controllers
|
||||||
wp_nav->shift_wp_origin_to_current_pos();
|
wp_nav->shift_wp_origin_and_destination_to_current_pos_xy();
|
||||||
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
|
pos_control->relax_alt_hold_controllers(0.0f); // forces throttle output to go to zero
|
||||||
pos_control->update_z_controller();
|
pos_control->update_z_controller();
|
||||||
attitude_control->set_yaw_target_to_current_heading();
|
attitude_control->set_yaw_target_to_current_heading();
|
||||||
|
Loading…
Reference in New Issue
Block a user