Made the Yaw on RTL always on for Helis

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2999 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-08-01 22:00:26 +00:00
parent 10d769a1d2
commit 6c75a03230
1 changed files with 7 additions and 1 deletions

View File

@ -280,9 +280,11 @@ static int motor_out[8];
// Heli
// ----
#if FRAME_CONFIG == HELI_FRAME
static float heli_rollFactor[3], heli_pitchFactor[3]; // only required for 3 swashplate servos
static int heli_servo_min[3], heli_servo_max[3]; // same here. for yaw servo we use heli_servo4_min/max parameter directly
static int heli_servo_out[4];
#endif
// Failsafe
// --------
@ -1321,16 +1323,20 @@ static void update_navigation()
break;
case GUIDED:
case RTL:
if(wp_distance > 20){
// calculates desired Yaw
// XXX this is an experiment
#if FRAME_CONFIG == HELI_FRAME
update_nav_yaw();
#endif
}else{
// Don't Yaw anymore
// hack to elmininate crosstrack effect
crosstrack_bearing = target_bearing;
}
case RTL:
// are we Traversing or Loitering?
wp_control = (wp_distance < 4 ) ? LOITER_MODE : WP_MODE;