From c86e53e922431ca4cf3a2dfe9bb2bc033551211a Mon Sep 17 00:00:00 2001 From: jasonshort Date: Mon, 5 Sep 2011 17:06:08 +0000 Subject: [PATCH] Fixed Log formatting Fixed Alt Hold setting error. git-svn-id: https://arducopter.googlecode.com/svn/trunk@3276 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/Log.pde | 9 +++------ ArduCopterMega/commands.pde | 3 ++- ArduCopterMega/config.h | 2 +- ArduCopterMega/system.pde | 2 ++ 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/ArduCopterMega/Log.pde b/ArduCopterMega/Log.pde index a029fb3c1f..9821f72c26 100644 --- a/ArduCopterMega/Log.pde +++ b/ArduCopterMega/Log.pde @@ -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(), diff --git a/ArduCopterMega/commands.pde b/ArduCopterMega/commands.pde index 2194ffd1c3..58964e0741 100644 --- a/ArduCopterMega/commands.pde +++ b/ArduCopterMega/commands.pde @@ -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; } diff --git a/ArduCopterMega/config.h b/ArduCopterMega/config.h index c4ab920e2f..379d0211c9 100644 --- a/ArduCopterMega/config.h +++ b/ArduCopterMega/config.h @@ -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 diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index bac0fb6da8..44fde00483 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -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;