Fixed Log formatting

Fixed Alt Hold setting error.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@3276 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-09-05 17:06:08 +00:00
parent 51473501bc
commit c86e53e922
4 changed files with 8 additions and 8 deletions

View File

@ -618,21 +618,18 @@ static void Log_Read_Control_Tuning()
{
Serial.printf_P(PSTR( "CTUN, "
"%d, %d, "
"%d, %d, %ld, "
"%d, %d, %ld, "
"%d, %d, %ld\n"),
"%d, %d, %d, "
"%d, %d, %d, "
"%d, %d, %d\n"),
// Control
DataFlash.ReadInt(),
DataFlash.ReadInt(),
// yaw
(int)DataFlash.ReadByte(),
DataFlash.ReadInt(),
DataFlash.ReadInt(),
DataFlash.ReadInt(),
//(float)DataFlash.ReadInt(),// Gyro Rate
DataFlash.ReadLong(),
// Alt Hold
DataFlash.ReadInt(),

View File

@ -234,7 +234,8 @@ static void init_home()
// Save prev loc this makes the calcs look better before commands are loaded
prev_WP = home;
next_WP = home;
// this is dangerous since we can get GPS lock at any time.
//next_WP = home;
}

View File

@ -522,7 +522,7 @@
//# define THROTTLE_D 0.6 // upped with filter
//#endif
#ifndef THROTTLE_IMAX
# define THROTTLE_IMAX 50
# define THROTTLE_IMAX 150
#endif

View File

@ -394,6 +394,7 @@ static void set_mode(byte mode)
throttle_mode = ALT_HOLD_THR;
init_throttle_cruise();
next_WP.alt = current_loc.alt;
break;
case AUTO:
@ -408,6 +409,7 @@ static void set_mode(byte mode)
init_auto();
// do crosstrack correction
// XXX move to flight commands
xtrack_enabled = true;
break;