Use the G_RC_AUX macro when possible. Added more comments. Remove unused code

This commit is contained in:
Amilcar Lucas 2011-09-12 20:03:44 +02:00
parent 5a14d546bb
commit f7f745055d
3 changed files with 11 additions and 22 deletions

View File

@ -39,7 +39,6 @@ version 2.1 of the License, or (at your option) any later version.
#include <AP_DCM.h> // ArduPilot Mega DCM Library #include <AP_DCM.h> // ArduPilot Mega DCM Library
#include <PID.h> // PID library #include <PID.h> // PID library
#include <RC_Channel.h> // RC Channel Library #include <RC_Channel.h> // RC Channel Library
//#include <RC_Channel/RC_Channel_aux.h> // Auxiliary RC Channel Library (Channels 5..8)
#include <AP_RangeFinder.h> // Range finder library #include <AP_RangeFinder.h> // Range finder library
#include <ModeFilter.h> #include <ModeFilter.h>
#include <AP_Camera.h> // Photo or video camera #include <AP_Camera.h> // Photo or video camera

View File

@ -274,14 +274,14 @@ static void set_servos(void)
} }
g.channel_throttle.radio_out = g.channel_throttle.radio_in; g.channel_throttle.radio_out = g.channel_throttle.radio_in;
g.channel_rudder.radio_out = g.channel_rudder.radio_in; g.channel_rudder.radio_out = g.channel_rudder.radio_in;
if (g_rc_function[RC_Channel_aux::k_aileron] != NULL) g_rc_function[RC_Channel_aux::k_aileron]->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in; G_RC_AUX(k_aileron)->radio_out = g_rc_function[RC_Channel_aux::k_aileron]->radio_in;
} else { } else {
if (g.mix_mode == 0) { if (g.mix_mode == 0) {
g.channel_roll.calc_pwm(); g.channel_roll.calc_pwm();
g.channel_pitch.calc_pwm(); g.channel_pitch.calc_pwm();
g.channel_rudder.calc_pwm(); g.channel_rudder.calc_pwm();
if (g_rc_function[RC_Channel_aux::k_aileron] != NULL) { if (g_rc_function[RC_Channel_aux::k_aileron]) {
g_rc_function[RC_Channel_aux::k_aileron]->servo_out = g.channel_roll.servo_out; g_rc_function[RC_Channel_aux::k_aileron]->servo_out = g.channel_roll.servo_out;
g_rc_function[RC_Channel_aux::k_aileron]->calc_pwm(); g_rc_function[RC_Channel_aux::k_aileron]->calc_pwm();
} }
@ -315,7 +315,7 @@ static void set_servos(void)
} }
if(control_mode <= FLY_BY_WIRE_B) { if(control_mode <= FLY_BY_WIRE_B) {
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in; G_RC_AUX(k_flap_auto)->radio_out = g_rc_function[RC_Channel_aux::k_flap_auto]->radio_in;
} else if (control_mode >= FLY_BY_WIRE_C) { } else if (control_mode >= FLY_BY_WIRE_C) {
if (g.airspeed_enabled == true) { if (g.airspeed_enabled == true) {
flapSpeedSource = g.airspeed_cruise; flapSpeedSource = g.airspeed_cruise;
@ -323,11 +323,11 @@ static void set_servos(void)
flapSpeedSource = g.throttle_cruise; flapSpeedSource = g.throttle_cruise;
} }
if ( flapSpeedSource > g.flap_1_speed) { if ( flapSpeedSource > g.flap_1_speed) {
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = 0; G_RC_AUX(k_flap_auto)->servo_out = 0;
} else if (flapSpeedSource > g.flap_2_speed) { } else if (flapSpeedSource > g.flap_2_speed) {
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_1_percent; G_RC_AUX(k_flap_auto)->servo_out = g.flap_1_percent;
} else { } else {
if (g_rc_function[RC_Channel_aux::k_flap_auto] != NULL) g_rc_function[RC_Channel_aux::k_flap_auto]->servo_out = g.flap_2_percent; G_RC_AUX(k_flap_auto)->servo_out = g.flap_2_percent;
} }
} }

View File

@ -21,6 +21,7 @@ RC_Channel_aux::closest_limit(int16_t angle)
while (min >= 1800) min -= 3600; while (min >= 1800) min -= 3600;
while (max < -1800) max += 3600; while (max < -1800) max += 3600;
while (max >= 1800) max -= 3600; while (max >= 1800) max -= 3600;
// This is done every time because the user might change the min, max values on the fly
set_range(min, max); set_range(min, max);
// If the angle is outside servo limits, saturate the angle to the closest limit // If the angle is outside servo limits, saturate the angle to the closest limit
@ -44,6 +45,7 @@ RC_Channel_aux::closest_limit(int16_t angle)
void void
RC_Channel_aux::output_ch(unsigned char ch_nr) RC_Channel_aux::output_ch(unsigned char ch_nr)
{ {
// take care or two corner cases
switch(function) switch(function)
{ {
case k_none: // disabled case k_none: // disabled
@ -52,26 +54,14 @@ RC_Channel_aux::output_ch(unsigned char ch_nr)
case k_manual: // manual case k_manual: // manual
radio_out = radio_in; radio_out = radio_in;
break; break;
case k_flap: // flaps
case k_flap_auto: // flaps automated
case k_aileron: // aileron
case k_flaperon: // flaperon (flaps and aileron combined, needs two independent servos one for each wing)
case k_mount_yaw: // mount yaw (pan)
case k_mount_pitch: // mount pitch (tilt)
case k_mount_roll: // mount roll
case k_cam_trigger: // camera trigger
case k_cam_open: // camera open
case k_egg_drop: // egg drop
case k_nr_aux_servo_functions: // dummy, just to avoid a compiler warning
default:
break;
} }
APM_RC.OutputCh(ch_nr, radio_out); APM_RC.OutputCh(ch_nr, radio_out);
} }
// update the g_rc_function array from pointers to rc_x channels // Update the g_rc_function array of pointers to rc_x channels
// This should be done periodically because the user might change the configuration and // This is to be done before rc_init so that the channels get correctly initialized.
// It also should be called periodically because the user might change the configuration and
// expects the changes to take effect instantly // expects the changes to take effect instantly
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) 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)
{ {