|
|
|
@ -114,9 +114,7 @@ static void auto_takeoff_run()
@@ -114,9 +114,7 @@ static void auto_takeoff_run()
|
|
|
|
|
// initialise wpnav targets |
|
|
|
|
wp_nav.shift_wp_origin_to_current_pos(); |
|
|
|
|
// reset attitude control targets |
|
|
|
|
attitude_control.relax_bf_rate_controller(); |
|
|
|
|
attitude_control.set_yaw_target_to_current_heading(); |
|
|
|
|
attitude_control.set_throttle_out(0, false); |
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true); |
|
|
|
|
// tell motors to do a slow start |
|
|
|
|
motors.slow_start(true); |
|
|
|
|
return; |
|
|
|
@ -162,9 +160,7 @@ static void auto_wp_run()
@@ -162,9 +160,7 @@ static void auto_wp_run()
|
|
|
|
|
if(!ap.auto_armed) { |
|
|
|
|
// To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off |
|
|
|
|
// (of course it would be better if people just used take-off) |
|
|
|
|
attitude_control.relax_bf_rate_controller(); |
|
|
|
|
attitude_control.set_yaw_target_to_current_heading(); |
|
|
|
|
attitude_control.set_throttle_out(0, false); |
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true); |
|
|
|
|
// tell motors to do a slow start |
|
|
|
|
motors.slow_start(true); |
|
|
|
|
return; |
|
|
|
@ -220,9 +216,7 @@ static void auto_spline_run()
@@ -220,9 +216,7 @@ static void auto_spline_run()
|
|
|
|
|
if(!ap.auto_armed) { |
|
|
|
|
// To-Do: reset waypoint origin to current location because copter is probably on the ground so we don't want it lurching left or right on take-off |
|
|
|
|
// (of course it would be better if people just used take-off) |
|
|
|
|
attitude_control.relax_bf_rate_controller(); |
|
|
|
|
attitude_control.set_yaw_target_to_current_heading(); |
|
|
|
|
attitude_control.set_throttle_out(0, false); |
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true); |
|
|
|
|
// tell motors to do a slow start |
|
|
|
|
motors.slow_start(true); |
|
|
|
|
return; |
|
|
|
@ -289,9 +283,7 @@ static void auto_land_run()
@@ -289,9 +283,7 @@ static void auto_land_run()
|
|
|
|
|
|
|
|
|
|
// if not auto armed set throttle to zero and exit immediately |
|
|
|
|
if(!ap.auto_armed || ap.land_complete) { |
|
|
|
|
attitude_control.relax_bf_rate_controller(); |
|
|
|
|
attitude_control.set_yaw_target_to_current_heading(); |
|
|
|
|
attitude_control.set_throttle_out(0, false); |
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true); |
|
|
|
|
// set target to current position |
|
|
|
|
wp_nav.init_loiter_target(); |
|
|
|
|
return; |
|
|
|
@ -457,9 +449,7 @@ void auto_loiter_run()
@@ -457,9 +449,7 @@ void auto_loiter_run()
|
|
|
|
|
{ |
|
|
|
|
// if not auto armed set throttle to zero and exit immediately |
|
|
|
|
if(!ap.auto_armed || ap.land_complete) { |
|
|
|
|
attitude_control.relax_bf_rate_controller(); |
|
|
|
|
attitude_control.set_yaw_target_to_current_heading(); |
|
|
|
|
attitude_control.set_throttle_out(0, false); |
|
|
|
|
attitude_control.set_throttle_out_unstabilized(0,true); |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|