Plane: APM2 doesn't have channel 9 PWM output

This commit is contained in:
Andrew Tridgell 2013-06-24 09:04:36 +10:00
parent 1132c0ae7c
commit 056e0ca40d
5 changed files with 19 additions and 9 deletions

View File

@ -850,7 +850,7 @@ static void update_aux(void)
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11, &g.rc_12); update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11, &g.rc_12);
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11); update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_10, &g.rc_11);
#else #else
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);
#endif #endif

View File

@ -709,12 +709,14 @@ static void set_servos(void)
g.rc_6.output_ch(CH_6); g.rc_6.output_ch(CH_6);
g.rc_7.output_ch(CH_7); g.rc_7.output_ch(CH_7);
g.rc_8.output_ch(CH_8); g.rc_8.output_ch(CH_8);
# if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
g.rc_9.output_ch(CH_9); g.rc_9.output_ch(CH_9);
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
g.rc_10.output_ch(CH_10); g.rc_10.output_ch(CH_10);
g.rc_11.output_ch(CH_11); g.rc_11.output_ch(CH_11);
# endif #endif
# if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
g.rc_12.output_ch(CH_12); g.rc_12.output_ch(CH_12);
# endif # endif
} }

View File

@ -386,8 +386,10 @@ public:
RC_Channel_aux rc_6; RC_Channel_aux rc_6;
RC_Channel_aux rc_7; RC_Channel_aux rc_7;
RC_Channel_aux rc_8; RC_Channel_aux rc_8;
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
RC_Channel_aux rc_9; RC_Channel_aux rc_9;
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
RC_Channel_aux rc_10; RC_Channel_aux rc_10;
RC_Channel_aux rc_11; RC_Channel_aux rc_11;
#endif #endif
@ -418,8 +420,10 @@ public:
rc_6 (CH_6), rc_6 (CH_6),
rc_7 (CH_7), rc_7 (CH_7),
rc_8 (CH_8), rc_8 (CH_8),
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
rc_9 (CH_9), rc_9 (CH_9),
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
rc_10 (CH_10), rc_10 (CH_10),
rc_11 (CH_11), rc_11 (CH_11),
#endif #endif

View File

@ -737,11 +737,13 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_8, "RC8_", RC_Channel_aux), GGROUP(rc_8, "RC8_", RC_Channel_aux),
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// @Group: RC9_ // @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_9, "RC9_", RC_Channel_aux), GGROUP(rc_9, "RC9_", RC_Channel_aux),
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
// @Group: RC10_ // @Group: RC10_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp // @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_10, "RC10_", RC_Channel_aux), GGROUP(rc_10, "RC10_", RC_Channel_aux),

View File

@ -41,7 +41,7 @@ static void init_rc_in()
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11, &g.rc_12); update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11, &g.rc_12);
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2 #elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_9, &g.rc_10, &g.rc_11); update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_10, &g.rc_11);
#else #else
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);
#endif #endif
@ -63,8 +63,10 @@ static void init_rc_out()
RC_Channel::rc_channel(i)->output_trim(); RC_Channel::rc_channel(i)->output_trim();
} }
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
servo_write(CH_9, g.rc_9.radio_trim); servo_write(CH_9, g.rc_9.radio_trim);
#endif
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_PX4
servo_write(CH_10, g.rc_10.radio_trim); servo_write(CH_10, g.rc_10.radio_trim);
servo_write(CH_11, g.rc_11.radio_trim); servo_write(CH_11, g.rc_11.radio_trim);
#endif #endif