mirror of https://github.com/ArduPilot/ardupilot
Moved a function from radio.pde to the RC_Channel_aux library. Now its more readable and reusable
This commit is contained in:
parent
b7a0d8836a
commit
f4998c3673
|
@ -339,10 +339,10 @@ static void set_servos(void)
|
|||
APM_RC.OutputCh(CH_3, g.channel_throttle.radio_out); // send to Servos
|
||||
APM_RC.OutputCh(CH_4, g.channel_rudder.radio_out); // send to Servos
|
||||
// Route configurable aux. functions to their respective servos
|
||||
aux_servo_out(&g.rc_5, CH_5);
|
||||
aux_servo_out(&g.rc_6, CH_6);
|
||||
aux_servo_out(&g.rc_7, CH_7);
|
||||
aux_servo_out(&g.rc_8, CH_8);
|
||||
g.rc_5.output_ch(CH_5);
|
||||
g.rc_6.output_ch(CH_6);
|
||||
g.rc_7.output_ch(CH_7);
|
||||
g.rc_8.output_ch(CH_8);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -247,34 +247,6 @@ static void trim_radio()
|
|||
if (g_rc_function[RC_Channel_aux::k_aileron] != NULL) g_rc_function[RC_Channel_aux::k_aileron]->save_eeprom();
|
||||
}
|
||||
|
||||
// map a function to a servo channel
|
||||
static void aux_servo_out(RC_Channel_aux* ch, unsigned char ch_nr)
|
||||
{
|
||||
switch(ch->function)
|
||||
{
|
||||
case RC_Channel_aux::k_none: // disabled
|
||||
return;
|
||||
break;
|
||||
case RC_Channel_aux::k_mount_yaw: // mount yaw (pan)
|
||||
case RC_Channel_aux::k_mount_pitch: // mount pitch (tilt)
|
||||
case RC_Channel_aux::k_mount_roll: // mount roll
|
||||
case RC_Channel_aux::k_cam_trigger: // camera trigger
|
||||
case RC_Channel_aux::k_cam_open: // camera open
|
||||
case RC_Channel_aux::k_flap: // flaps
|
||||
case RC_Channel_aux::k_flap_auto: // flaps automated
|
||||
case RC_Channel_aux::k_aileron: // aileron
|
||||
case RC_Channel_aux::k_flaperon: // flaperon (flaps and aileron combined, needs two independent servos one for each wing)
|
||||
case RC_Channel_aux::k_egg_drop: // egg drop
|
||||
case RC_Channel_aux::k_nr_aux_servo_functions: // dummy, just to avoid a compiler warning
|
||||
break;
|
||||
case RC_Channel_aux::k_manual: // manual
|
||||
ch->radio_out = ch->radio_in;
|
||||
break;
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(ch_nr, ch->radio_out);
|
||||
}
|
||||
|
||||
// update the g_rc_function array from pointers to rc_x channels
|
||||
static void update_aux_servo_function()
|
||||
{
|
||||
|
|
|
@ -11,6 +11,7 @@
|
|||
|
||||
#include <math.h>
|
||||
#include <avr/eeprom.h>
|
||||
#include <APM_RC.h>
|
||||
#include "WProgram.h"
|
||||
#include "RC_Channel.h"
|
||||
|
||||
|
@ -253,3 +254,32 @@ RC_Channel_aux::closest_limit(int16_t angle)
|
|||
|
||||
return angle;
|
||||
}
|
||||
|
||||
// map a function to a servo channel and output it
|
||||
void
|
||||
RC_Channel_aux::output_ch(unsigned char ch_nr)
|
||||
{
|
||||
switch(function)
|
||||
{
|
||||
case k_none: // disabled
|
||||
return;
|
||||
break;
|
||||
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_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_egg_drop: // egg drop
|
||||
case k_nr_aux_servo_functions: // dummy, just to avoid a compiler warning
|
||||
break;
|
||||
case k_manual: // manual
|
||||
radio_out = radio_in;
|
||||
break;
|
||||
}
|
||||
|
||||
APM_RC.OutputCh(ch_nr, radio_out);
|
||||
}
|
||||
|
|
|
@ -144,6 +144,9 @@ public:
|
|||
AP_Int16 angle_max; // max angle limit of actuated surface in 0.01 degree units
|
||||
|
||||
int16_t closest_limit(int16_t angle); // saturate to the closest angle limit if outside of min max angle interval
|
||||
|
||||
void output_ch(unsigned char ch_nr); // map a function to a servo channel and output it
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue