Added support for WP options

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1743 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-03-05 05:12:16 +00:00
parent afa8be2008
commit 0b2d94950f
3 changed files with 6 additions and 1 deletions

View File

@ -959,6 +959,7 @@ void update_navigation()
// distance and bearing calcs only
if(control_mode == AUTO || control_mode == GCS_AUTO){
verify_commands();
}else{
switch(control_mode){
case RTL:

View File

@ -255,5 +255,8 @@ void output_manual_yaw()
void auto_yaw()
{
if(next_WP.options & WP_OPT_YAW){
nav_yaw = target_bearing;
}
output_yaw_with_hold(true); // hold yaw
}

View File

@ -101,8 +101,9 @@ void calc_bearing_error()
void calc_altitude_error()
{
//if(control_mode == AUTO && offset_altitude != 0) {
if(next_WP.options & WP_OPT_ALT_CHANGE) {
if(next_WP.options & WP_OPT_ALT_CHANGE || offset_altitude == 0) {
target_altitude = next_WP.alt;
}else{
// limit climb rates - we draw a straight line between first location and edge of waypoint_radius
target_altitude = next_WP.alt - ((wp_distance * offset_altitude) / (wp_totalDistance - g.waypoint_radius));