From d2a4091716621854c8f2ca9bb3bd3cd9c45e8f56 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 12 Feb 2012 22:32:06 +1100 Subject: [PATCH] fixed apm2beta build with AP_Param --- ArduCopter/ArduCopter.pde | 2 +- ArduCopter/GCS_Mavlink.pde | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 6a19cdb90c..7b2dfe3a30 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -179,7 +179,7 @@ static AP_Int8 *flight_modes = &g.flight_mode1; AP_Baro_MS5611 barometer; #endif - AP_Compass_HMC5843 compass(Parameters::k_param_compass); + AP_Compass_HMC5843 compass; #endif #ifdef OPTFLOW_ENABLED diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 77a1ece189..7c7b97a017 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1415,13 +1415,13 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) ((AP_Int32 *)vp)->set_and_save(packet.param_value+rounding_addition); } else if (var_type == AP_PARAM_INT16) { #if LOGGING_ENABLED == ENABLED - Log_Write_Data(3, ((AP_Int16 *)vp)->get()); + Log_Write_Data(3, (int32_t)((AP_Int16 *)vp)->get()); #endif if (packet.param_value < 0) rounding_addition = -rounding_addition; ((AP_Int16 *)vp)->set_and_save(packet.param_value+rounding_addition); } else if (var_type == AP_PARAM_INT8) { #if LOGGING_ENABLED == ENABLED - Log_Write_Data(4, ((AP_Int8 *)vp)->get()); + Log_Write_Data(4, (int32_t)((AP_Int8 *)vp)->get()); #endif if (packet.param_value < 0) rounding_addition = -rounding_addition; ((AP_Int8 *)vp)->set_and_save(packet.param_value+rounding_addition);