Browse Source

Revert more of 6dcbc7f44bc0.

Fix an issue with initialization of channels that on-line changed their function.
For the curious people that the code size overhead of having any aux channel do any function (with this code) is 44 bytes.
 To see wich code I'm talking about, do a git diff 05057ac2d455..this_commit (replace this commit with the commit hash of this commit)
mission-4.1.18
Amilcar Lucas 14 years ago
parent
commit
1f29197771
  1. 4
      ArduPlane/radio.pde
  2. 5
      libraries/RC_Channel/RC_Channel_aux.cpp
  3. 7
      libraries/RC_Channel/RC_Channel_aux.h

4
ArduPlane/radio.pde

@ -24,10 +24,6 @@ static void init_rc_in() @@ -24,10 +24,6 @@ static void init_rc_in()
//set auxiliary ranges
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
G_RC_AUX(k_flap)->set_range(0,100);
G_RC_AUX(k_flap_auto)->set_range(0,100);
G_RC_AUX(k_aileron)->set_angle(SERVO_MAX);
G_RC_AUX(k_flaperon)->set_range(0,100);
}
static void init_rc_out()

5
libraries/RC_Channel/RC_Channel_aux.cpp

@ -47,4 +47,9 @@ void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Ch @@ -47,4 +47,9 @@ void update_aux_servo_function(RC_Channel_aux* rc_5, RC_Channel_aux* rc_6, RC_Ch
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_AUX(k_flap)->set_range(0,100);
G_RC_AUX(k_flap_auto)->set_range(0,100);
G_RC_AUX(k_aileron)->set_angle(4500);
G_RC_AUX(k_flaperon)->set_range(0,100);
}

7
libraries/RC_Channel/RC_Channel_aux.h

@ -14,7 +14,6 @@ @@ -14,7 +14,6 @@
/// @class RC_Channel_aux
/// @brief Object managing one aux. RC channel (CH5-8), with information about its function
/// Also contains physical min,max angular deflection, to allow calibrating open-loop servo movements
class RC_Channel_aux : public RC_Channel{
public:
/// Constructor
@ -24,9 +23,7 @@ public: @@ -24,9 +23,7 @@ public:
///
RC_Channel_aux(AP_Var::Key key, const prog_char_t *name) :
RC_Channel(key, name),
function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0), // suppress name if group has no name
angle_min (&_group, 5, -4500, name ? PSTR("ANGLE_MIN") : 0), // assume -45 degrees min deflection
angle_max (&_group, 6, 4500, name ? PSTR("ANGLE_MAX") : 0) // assume 45 degrees max deflection
function (&_group, 4, k_none, name ? PSTR("FUNCTION") : 0) // suppress name if group has no name
{}
typedef enum
@ -41,8 +38,6 @@ public: @@ -41,8 +38,6 @@ public:
} Aux_servo_function_t;
AP_Int8 function; // 0=disabled, 1=manual, 2=flap, 3=flap auto, 4=aileron, 5=flaperon, 6=mount yaw (pan), 7=mount pitch (tilt), 8=mount roll, 9=camera trigger, 10=camera open, 11=egg drop
AP_Int16 angle_min; // min angle limit of actuated surface in 0.01 degree units
AP_Int16 angle_max; // max angle limit of actuated surface in 0.01 degree units
void output_ch(unsigned char ch_nr); // map a function to a servo channel and output it

Loading…
Cancel
Save