mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
More flexible RC support
This commit is contained in:
parent
d29f7023cc
commit
bbc4bdb729
@ -4,6 +4,9 @@
|
|||||||
// ----------------------------------------------------------------------------
|
// ----------------------------------------------------------------------------
|
||||||
static int8_t failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
static int8_t failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
||||||
|
|
||||||
|
|
||||||
|
extern RC_Channel* rc_ch[8];
|
||||||
|
|
||||||
static void default_dead_zones()
|
static void default_dead_zones()
|
||||||
{
|
{
|
||||||
g.rc_1.set_dead_zone(60);
|
g.rc_1.set_dead_zone(60);
|
||||||
@ -37,6 +40,15 @@ static void init_rc_in()
|
|||||||
g.rc_2.set_type(RC_CHANNEL_ANGLE_RAW);
|
g.rc_2.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||||
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
|
g.rc_4.set_type(RC_CHANNEL_ANGLE_RAW);
|
||||||
|
|
||||||
|
rc_ch[CH_1] = &g.rc_1;
|
||||||
|
rc_ch[CH_2] = &g.rc_2;
|
||||||
|
rc_ch[CH_3] = &g.rc_3;
|
||||||
|
rc_ch[CH_4] = &g.rc_4;
|
||||||
|
rc_ch[CH_5] = &g.rc_5;
|
||||||
|
rc_ch[CH_6] = &g.rc_6;
|
||||||
|
rc_ch[CH_7] = &g.rc_7;
|
||||||
|
rc_ch[CH_8] = &g.rc_8;
|
||||||
|
|
||||||
//set auxiliary ranges
|
//set auxiliary ranges
|
||||||
g.rc_5.set_range(0,1000);
|
g.rc_5.set_range(0,1000);
|
||||||
g.rc_6.set_range(0,1000);
|
g.rc_6.set_range(0,1000);
|
||||||
@ -51,6 +63,12 @@ static void init_rc_in()
|
|||||||
static void init_rc_out()
|
static void init_rc_out()
|
||||||
{
|
{
|
||||||
APM_RC.Init( &isr_registry ); // APM Radio initialization
|
APM_RC.Init( &isr_registry ); // APM Radio initialization
|
||||||
|
|
||||||
|
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1
|
||||||
|
APM_RC.enable_out(CH_9);
|
||||||
|
APM_RC.enable_out(CH_10);
|
||||||
|
APM_RC.enable_out(CH_11);
|
||||||
|
#endif
|
||||||
#if INSTANT_PWM == 1
|
#if INSTANT_PWM == 1
|
||||||
motors.set_update_rate(AP_MOTORS_SPEED_INSTANT_PWM);
|
motors.set_update_rate(AP_MOTORS_SPEED_INSTANT_PWM);
|
||||||
#else
|
#else
|
||||||
|
@ -5,6 +5,8 @@
|
|||||||
static byte failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
static byte failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
||||||
|
|
||||||
|
|
||||||
|
extern RC_Channel* rc_ch[8];
|
||||||
|
|
||||||
static void init_rc_in()
|
static void init_rc_in()
|
||||||
{
|
{
|
||||||
// set rc reversing
|
// set rc reversing
|
||||||
@ -27,6 +29,15 @@ static void init_rc_in()
|
|||||||
//g.channel_rudder.dead_zone = 60;
|
//g.channel_rudder.dead_zone = 60;
|
||||||
//g.channel_throttle.dead_zone = 6;
|
//g.channel_throttle.dead_zone = 6;
|
||||||
|
|
||||||
|
rc_ch[CH_1] = &g.channel_roll;
|
||||||
|
rc_ch[CH_2] = &g.channel_pitch;
|
||||||
|
rc_ch[CH_3] = &g.channel_throttle;
|
||||||
|
rc_ch[CH_4] = &g.channel_rudder;
|
||||||
|
rc_ch[CH_5] = &g.rc_5;
|
||||||
|
rc_ch[CH_6] = &g.rc_6;
|
||||||
|
rc_ch[CH_7] = &g.rc_7;
|
||||||
|
rc_ch[CH_8] = &g.rc_8;
|
||||||
|
|
||||||
//set auxiliary ranges
|
//set auxiliary ranges
|
||||||
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM1
|
||||||
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
|
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8);
|
||||||
@ -48,6 +59,12 @@ static void init_rc_out()
|
|||||||
APM_RC.enable_out(CH_7);
|
APM_RC.enable_out(CH_7);
|
||||||
APM_RC.enable_out(CH_8);
|
APM_RC.enable_out(CH_8);
|
||||||
|
|
||||||
|
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1
|
||||||
|
APM_RC.enable_out(CH_9);
|
||||||
|
APM_RC.enable_out(CH_10);
|
||||||
|
APM_RC.enable_out(CH_11);
|
||||||
|
#endif
|
||||||
|
|
||||||
APM_RC.OutputCh(CH_1, g.channel_roll.radio_trim); // Initialization of servo outputs
|
APM_RC.OutputCh(CH_1, g.channel_roll.radio_trim); // Initialization of servo outputs
|
||||||
APM_RC.OutputCh(CH_2, g.channel_pitch.radio_trim);
|
APM_RC.OutputCh(CH_2, g.channel_pitch.radio_trim);
|
||||||
APM_RC.OutputCh(CH_3, g.channel_throttle.radio_min);
|
APM_RC.OutputCh(CH_3, g.channel_throttle.radio_min);
|
||||||
@ -55,8 +72,14 @@ static void init_rc_out()
|
|||||||
|
|
||||||
APM_RC.OutputCh(CH_5, g.rc_5.radio_trim);
|
APM_RC.OutputCh(CH_5, g.rc_5.radio_trim);
|
||||||
APM_RC.OutputCh(CH_6, g.rc_6.radio_trim);
|
APM_RC.OutputCh(CH_6, g.rc_6.radio_trim);
|
||||||
APM_RC.OutputCh(CH_7, g.rc_7.radio_trim);
|
APM_RC.OutputCh(CH_7, g.rc_7.radio_trim);
|
||||||
APM_RC.OutputCh(CH_8, g.rc_8.radio_trim);
|
APM_RC.OutputCh(CH_8, g.rc_8.radio_trim);
|
||||||
|
|
||||||
|
#if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1
|
||||||
|
APM_RC.OutputCh(CH_9, g.rc_9.radio_trim);
|
||||||
|
APM_RC.OutputCh(CH_10, g.rc_10.radio_trim);
|
||||||
|
APM_RC.OutputCh(CH_11, g.rc_11.radio_trim);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void read_radio()
|
static void read_radio()
|
||||||
|
@ -22,6 +22,10 @@
|
|||||||
#define RC_CHANNEL_RANGE 1
|
#define RC_CHANNEL_RANGE 1
|
||||||
#define RC_CHANNEL_ANGLE_RAW 2
|
#define RC_CHANNEL_ANGLE_RAW 2
|
||||||
|
|
||||||
|
/// global array with pointers to all APM RC channels, will be used by AP_Mount and AP_Camera classes
|
||||||
|
/// It points to RC input channels, both APM1 and APM2 only have 8 input channels.
|
||||||
|
RC_Channel* rc_ch[8];
|
||||||
|
|
||||||
APM_RC_Class *RC_Channel::_apm_rc;
|
APM_RC_Class *RC_Channel::_apm_rc;
|
||||||
|
|
||||||
const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
const AP_Param::GroupInfo RC_Channel::var_info[] PROGMEM = {
|
||||||
|
Loading…
Reference in New Issue
Block a user