Added resetting of Loiter location based on stick input. Fly it to a location and let it stick.

Added Octo Support
Fixed Loiter issue regarding Yaw towards loiter location
Added Yaw control alternative for testing
decreased Yaw deadband to +-5°
revved to 2.0.10



git-svn-id: https://arducopter.googlecode.com/svn/trunk@2390 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-05-24 02:18:30 +00:00
parent 2118931cdc
commit 2a3b994d51
1 changed files with 7 additions and 4 deletions

View File

@ -281,11 +281,14 @@ output_yaw_with_hold(boolean hold)
rate = constrain(rate, -36000, 36000); // limit to something fun!
int dampener = rate * g.pid_yaw.kD(); // 34377 * .175 = 6000
// re-define nav_yaw if we have stick input
if(g.rc_4.control_in != 0){
// set nav_yaw + or - the current location
nav_yaw = (long)g.rc_4.control_in + dcm.yaw_sensor;
// we need to wrap our value so we can be 0 to 360 (*100)
nav_yaw = wrap_360(nav_yaw);
}
// how far off is nav_yaw from our current yaw?
yaw_error = nav_yaw - dcm.yaw_sensor;