Copter: use new throttle interface

This commit is contained in:
Jonathan Challinger 2015-03-25 01:15:24 -07:00 committed by Randy Mackay
parent f3555d0d43
commit b27b9dd86e
14 changed files with 32 additions and 83 deletions

View File

@ -20,9 +20,7 @@ static void acro_run()
// if motors not running reset angle targets // if motors not running reset angle targets
if(!motors.armed() || g.rc_3.control_in <= 0) { if(!motors.armed() || g.rc_3.control_in <= 0) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
return; return;
} }

View File

@ -27,9 +27,7 @@ static void althold_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) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -57,10 +55,7 @@ static void althold_run()
// reset target lean angles and heading while landed // reset target lean angles and heading while landed
if (ap.land_complete) { if (ap.land_complete) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true);
attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
}else{ }else{
// call attitude controller // call attitude controller

View File

@ -114,9 +114,7 @@ static void auto_takeoff_run()
// initialise wpnav targets // initialise wpnav targets
wp_nav.shift_wp_origin_to_current_pos(); wp_nav.shift_wp_origin_to_current_pos();
// reset attitude control targets // reset attitude control targets
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
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);
return; return;
@ -162,9 +160,7 @@ static void auto_wp_run()
if(!ap.auto_armed) { 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 // 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) // (of course it would be better if people just used take-off)
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
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);
return; return;
@ -220,9 +216,7 @@ static void auto_spline_run()
if(!ap.auto_armed) { 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 // 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) // (of course it would be better if people just used take-off)
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
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);
return; return;
@ -289,9 +283,7 @@ static void auto_land_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 || ap.land_complete) { if(!ap.auto_armed || ap.land_complete) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// set target to current position // set target to current position
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
return; return;
@ -457,9 +449,7 @@ void auto_loiter_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 || ap.land_complete) { if(!ap.auto_armed || ap.land_complete) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
return; return;
} }

View File

@ -263,9 +263,7 @@ static void autotune_run()
// if not auto armed set throttle to zero and exit immediately // if not auto armed set throttle to zero and exit immediately
// this should not actually be possible because of the autotune_init() checks // this should not actually be possible because of the autotune_init() checks
if (!ap.auto_armed) { if (!ap.auto_armed) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -292,10 +290,8 @@ static void autotune_run()
// reset target lean angles and heading while landed // reset target lean angles and heading while landed
if (ap.land_complete) { if (ap.land_complete) {
attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false); attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
}else{ }else{
// check if pilot is overriding the controls // check if pilot is overriding the controls

View File

@ -35,9 +35,7 @@ static void circle_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 || ap.land_complete) { if(!ap.auto_armed || ap.land_complete) {
// To-Do: add some initialisation of position controllers // To-Do: add some initialisation of position controllers
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
return; return;
} }

View File

@ -48,9 +48,7 @@ static void drift_run()
// if not armed or landed and throttle at zero, set throttle to zero and exit immediately // if not armed or landed and throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || (ap.land_complete && ap.throttle_zero)) { if(!motors.armed() || (ap.land_complete && ap.throttle_zero)) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
return; return;
} }

View File

@ -218,5 +218,9 @@ static void flip_run()
} }
// output pilot's throttle without angle boost // output pilot's throttle without angle boost
if (throttle_out == 0.0f) {
attitude_control.set_throttle_out_unstabilized(0,false);
} else {
attitude_control.set_throttle_out(throttle_out, false); attitude_control.set_throttle_out(throttle_out, false);
} }
}

View File

@ -161,9 +161,7 @@ static void guided_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) {
// To-Do: reset waypoint controller? // To-Do: reset waypoint controller?
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// To-Do: handle take-offs - these may not only be immediately after auto_armed becomes true // To-Do: handle take-offs - these may not only be immediately after auto_armed becomes true
return; return;
} }
@ -202,9 +200,7 @@ static void guided_takeoff_run()
// initialise wpnav targets // initialise wpnav targets
wp_nav.shift_wp_origin_to_current_pos(); wp_nav.shift_wp_origin_to_current_pos();
// reset attitude control targets // reset attitude control targets
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
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);
return; return;

View File

@ -52,9 +52,7 @@ static void land_gps_run()
// if not auto armed or landed set throttle to zero and exit immediately // if not auto armed or landed set throttle to zero and exit immediately
if(!ap.auto_armed || ap.land_complete) { if(!ap.auto_armed || ap.land_complete) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
@ -127,9 +125,7 @@ static void land_nogps_run()
// if not auto armed or landed set throttle to zero and exit immediately // if not auto armed or landed set throttle to zero and exit immediately
if(!ap.auto_armed || ap.land_complete) { if(!ap.auto_armed || ap.land_complete) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
#if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED #if LAND_REQUIRE_MIN_THROTTLE_TO_DISARM == ENABLED
// disarm when the landing detector says we've landed and throttle is at minimum // disarm when the landing detector says we've landed and throttle is at minimum
if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) { if (ap.land_complete && (ap.throttle_zero || failsafe.radio)) {

View File

@ -35,9 +35,7 @@ static void loiter_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) {
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -76,10 +74,8 @@ static void loiter_run()
// when landed reset targets and output zero throttle // when landed reset targets and output zero throttle
if (ap.land_complete) { if (ap.land_complete) {
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false); attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
}else{ }else{
// run loiter controller // run loiter controller

View File

@ -156,9 +156,7 @@ static void poshold_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) {
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -191,10 +189,8 @@ static void poshold_run()
// if landed initialise loiter targets, set throttle to zero and exit // if landed initialise loiter targets, set throttle to zero and exit
if (ap.land_complete) { if (ap.land_complete) {
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false); attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
return; return;
}else{ }else{

View File

@ -134,9 +134,7 @@ static void rtl_climb_return_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) {
// reset attitude control targets // reset attitude control targets
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// To-Do: re-initialise wpnav targets // To-Do: re-initialise wpnav targets
return; return;
} }
@ -192,9 +190,7 @@ static void rtl_loiterathome_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) {
// reset attitude control targets // reset attitude control targets
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// To-Do: re-initialise wpnav targets // To-Do: re-initialise wpnav targets
return; return;
} }
@ -263,9 +259,7 @@ static void rtl_descent_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) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// set target to current position // set target to current position
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();
return; return;
@ -327,9 +321,7 @@ static void rtl_land_run()
float target_yaw_rate = 0; float target_yaw_rate = 0;
// 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 || ap.land_complete) { if(!ap.auto_armed || ap.land_complete) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
// set target to current position // set target to current position
wp_nav.init_loiter_target(); wp_nav.init_loiter_target();

View File

@ -26,9 +26,7 @@ static void sport_run()
// if not armed or throttle at zero, set throttle to zero and exit immediately // if not armed or throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || g.rc_3.control_in <= 0) { if(!motors.armed() || g.rc_3.control_in <= 0) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
return; return;
} }
@ -77,10 +75,8 @@ static void sport_run()
// reset target lean angles and heading while landed // reset target lean angles and heading while landed
if (ap.land_complete) { if (ap.land_complete) {
attitude_control.relax_bf_rate_controller();
attitude_control.set_yaw_target_to_current_heading();
// move throttle to between minimum and non-takeoff-throttle to keep us on the ground // move throttle to between minimum and non-takeoff-throttle to keep us on the ground
attitude_control.set_throttle_out(get_throttle_pre_takeoff(g.rc_3.control_in), false); attitude_control.set_throttle_out_unstabilized(get_throttle_pre_takeoff(g.rc_3.control_in),true);
pos_control.set_alt_target_to_current_alt(); pos_control.set_alt_target_to_current_alt();
}else{ }else{

View File

@ -25,9 +25,7 @@ static void stabilize_run()
// if not armed or throttle at zero, set throttle to zero and exit immediately // if not armed or throttle at zero, set throttle to zero and exit immediately
if(!motors.armed() || g.rc_3.control_in <= 0) { if(!motors.armed() || g.rc_3.control_in <= 0) {
attitude_control.relax_bf_rate_controller(); attitude_control.set_throttle_out_unstabilized(0,true);
attitude_control.set_yaw_target_to_current_heading();
attitude_control.set_throttle_out(0, false);
return; return;
} }