Copter: control_stabilize reports alt target

This commit is contained in:
Randy Mackay 2014-01-10 16:20:08 +09:00 committed by Andrew Tridgell
parent 3ce1c0a9d5
commit 44e731ea40
1 changed files with 4 additions and 3 deletions

View File

@ -41,6 +41,9 @@ static void acro_run()
// stabilize_init - initialise stabilize controller // stabilize_init - initialise stabilize controller
static bool stabilize_init() static bool stabilize_init()
{ {
// set target altitude to zero for reporting
// To-Do: make pos controller aware when it's active/inactive so it can always report the altitude error?
pos_control.set_alt_target(0);
return true; return true;
} }
@ -144,7 +147,6 @@ static void althold_run()
// To-Do: set target angles to zero or current attitude? // To-Do: set target angles to zero or current attitude?
// To-Do: reset altitude target if we're somehow not landed? // To-Do: reset altitude target if we're somehow not landed?
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
set_target_alt_for_reporting(0);
return; return;
} }
@ -207,7 +209,6 @@ static void althold_run()
}else{ }else{
// move throttle to minimum to keep us on the ground // move throttle to minimum to keep us on the ground
attitude_control.set_throttle_out(0, false); attitude_control.set_throttle_out(0, false);
set_target_alt_for_reporting(0);
// To-Do: should return here because we don't want throttle out to be overwritten below // To-Do: should return here because we don't want throttle out to be overwritten below
} }
} }