Copter: shift pos targets to current location before takeoff

This commit is contained in:
Randy Mackay 2014-09-29 15:26:54 +09:00
parent 2d7f819e1d
commit da2a463f18
2 changed files with 4 additions and 2 deletions

View File

@ -102,13 +102,14 @@ static void auto_takeoff_run()
{ {
// if not auto armed set throttle to zero and exit immediately // if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed) { if(!ap.auto_armed) {
// initialise wpnav targets
wp_nav.shift_wp_origin_to_current_pos();
// reset attitude control targets // reset attitude control targets
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
// tell motors to do a slow start // tell motors to do a slow start
motors.slow_start(true); motors.slow_start(true);
// To-Do: re-initialise wpnav targets
return; return;
} }

View File

@ -140,13 +140,14 @@ static void guided_takeoff_run()
{ {
// if not auto armed set throttle to zero and exit immediately // if not auto armed set throttle to zero and exit immediately
if(!ap.auto_armed) { if(!ap.auto_armed) {
// initialise wpnav targets
wp_nav.shift_wp_origin_to_current_pos();
// reset attitude control targets // reset attitude control targets
attitude_control.relax_bf_rate_controller(); attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading(); attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
// tell motors to do a slow start // tell motors to do a slow start
motors.slow_start(true); motors.slow_start(true);
// To-Do: re-initialise wpnav targets
return; return;
} }