From 085cc00c334663f821d5ea85fa7d501704fdf733 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 14 Feb 2012 17:46:59 +1100 Subject: [PATCH] RC_Channel_aux: fixed a uninitialied variable error, and save a bit of stack space --- libraries/RC_Channel/RC_Channel_aux.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/libraries/RC_Channel/RC_Channel_aux.cpp b/libraries/RC_Channel/RC_Channel_aux.cpp index 3f2ab51080..3a074c6a79 100644 --- a/libraries/RC_Channel/RC_Channel_aux.cpp +++ b/libraries/RC_Channel/RC_Channel_aux.cpp @@ -74,13 +74,13 @@ RC_Channel_aux::output_ch(unsigned char ch_nr) void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Channel_aux* rc_7, RC_Channel_aux* rc_8) { // positions 0..3 of this array never get used, but this is a stack array, so the entire array gets freed at the end of the function - RC_Channel_aux::Aux_servo_function_t aux_servo_function[NUM_CHANNELS]; // the function of the aux. servos - aux_servo_function[CH_5] = (RC_Channel_aux::Aux_servo_function_t)rc_5->function.get(); - aux_servo_function[CH_6] = (RC_Channel_aux::Aux_servo_function_t)rc_6->function.get(); - aux_servo_function[CH_7] = (RC_Channel_aux::Aux_servo_function_t)rc_7->function.get(); - aux_servo_function[CH_8] = (RC_Channel_aux::Aux_servo_function_t)rc_8->function.get(); + RC_Channel_aux::Aux_servo_function_t aux_servo_function[4]; + aux_servo_function[0] = (RC_Channel_aux::Aux_servo_function_t)rc_5->function.get(); + aux_servo_function[1] = (RC_Channel_aux::Aux_servo_function_t)rc_6->function.get(); + aux_servo_function[2] = (RC_Channel_aux::Aux_servo_function_t)rc_7->function.get(); + aux_servo_function[3] = (RC_Channel_aux::Aux_servo_function_t)rc_8->function.get(); - for (uint8_t i = 0; i < NUM_CHANNELS; i++) { + for (uint8_t i = 0; i < 4; i++) { if (aux_servo_function[i] >= RC_Channel_aux::k_nr_aux_servo_functions) { // invalid setting aux_servo_function[i] = RC_Channel_aux::k_none; @@ -94,10 +94,10 @@ void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Ch } // assign the RC channel to each function - g_rc_function[aux_servo_function[CH_5]] = rc_5; - g_rc_function[aux_servo_function[CH_6]] = rc_6; - g_rc_function[aux_servo_function[CH_7]] = rc_7; - g_rc_function[aux_servo_function[CH_8]] = rc_8; + g_rc_function[aux_servo_function[0]] = rc_5; + g_rc_function[aux_servo_function[1]] = rc_6; + g_rc_function[aux_servo_function[2]] = rc_7; + g_rc_function[aux_servo_function[3]] = rc_8; //set auxiliary ranges G_RC_AUX(k_flap)->set_range(0,100);