From abd0fb90990e20d0ebdfb93ca0ff032d4bf53d09 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 21 Feb 2013 22:23:03 -0800 Subject: [PATCH] AC : global static variables should not be initialized to zero --- ArduCopter/ArduCopter.pde | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index c8e37ed791..6460a5328d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -561,12 +561,12 @@ static int32_t initial_simple_bearing; // Rate contoller targets //////////////////////////////////////////////////////////////////////////////// static uint8_t rate_targets_frame = EARTH_FRAME; // indicates whether rate targets provided in earth or body frame -static int32_t roll_rate_target_ef = 0; -static int32_t pitch_rate_target_ef = 0; -static int32_t yaw_rate_target_ef = 0; -static int32_t roll_rate_target_bf = 0; // body frame roll rate target -static int32_t pitch_rate_target_bf = 0; // body frame pitch rate target -static int32_t yaw_rate_target_bf = 0; // body frame yaw rate target +static int32_t roll_rate_target_ef; +static int32_t pitch_rate_target_ef; +static int32_t yaw_rate_target_ef; +static int32_t roll_rate_target_bf; // body frame roll rate target +static int32_t pitch_rate_target_bf; // body frame pitch rate target +static int32_t yaw_rate_target_bf; // body frame yaw rate target //////////////////////////////////////////////////////////////////////////////// // Throttle variables