From 3caaa27526c01bdb1a9a925add9457912e71f54b Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 27 Jan 2013 12:58:50 +1100 Subject: [PATCH] Plane: fixed build errors in logging --- ArduPlane/ArduPlane.pde | 2 +- ArduPlane/Log.pde | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 8eaa396d28..83d6cd2c91 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -588,7 +588,7 @@ static int32_t perf_mon_timer; // The maximum main loop execution time recorded in the current performance monitoring interval static int16_t G_Dt_max = 0; // The number of gps fixes recorded in the current performance monitoring interval -static int16_t gps_fix_count = 0; +static uint8_t gps_fix_count = 0; // A variable used by developers to track performanc metrics. // Currently used to record the number of GCS heartbeat messages received static int16_t pmTest1 = 0; diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index 4a1c8d0939..5e02a170a9 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -407,7 +407,7 @@ static void Log_Write_Control_Tuning() pitch : (int16_t)ahrs.pitch_sensor, throttle_out : (int16_t)g.channel_throttle.servo_out, rudder_out : (int16_t)g.channel_rudder.servo_out, - accel_y : (int16_t)accel.y * 10000 + accel_y : (int16_t)(accel.y * 10000) }; DataFlash.WriteBlock(&pkt, sizeof(pkt)); } @@ -586,8 +586,8 @@ static void Log_Write_Current() struct log_Current pkt = { LOG_PACKET_HEADER_INIT(LOG_CURRENT_MSG), throttle_in : g.channel_throttle.control_in, - battery_voltage : (int16_t)battery_voltage1 * 100.0, - current_amps : (int16_t)current_amps1 * 100.0, + battery_voltage : (int16_t)(battery_voltage1 * 100.0), + current_amps : (int16_t)(current_amps1 * 100.0), current_total : (int16_t)current_total1 }; DataFlash.WriteBlock(&pkt, sizeof(pkt));