mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
Plane: support 14 RC channels on PX4
This commit is contained in:
parent
c0767eebff
commit
ff70c87f0b
@ -975,6 +975,8 @@ static void set_servos(void)
|
|||||||
#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);
|
||||||
|
g.rc_13.output_ch(CH_13);
|
||||||
|
g.rc_14.output_ch(CH_14);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -218,6 +218,8 @@ public:
|
|||||||
k_param_fs_batt_mah,
|
k_param_fs_batt_mah,
|
||||||
k_param_short_fs_timeout,
|
k_param_short_fs_timeout,
|
||||||
k_param_long_fs_timeout,
|
k_param_long_fs_timeout,
|
||||||
|
k_param_rc_13,
|
||||||
|
k_param_rc_14,
|
||||||
|
|
||||||
//
|
//
|
||||||
// 200: Feed-forward gains
|
// 200: Feed-forward gains
|
||||||
@ -442,6 +444,8 @@ public:
|
|||||||
#endif
|
#endif
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
RC_Channel_aux rc_12;
|
RC_Channel_aux rc_12;
|
||||||
|
RC_Channel_aux rc_13;
|
||||||
|
RC_Channel_aux rc_14;
|
||||||
#endif
|
#endif
|
||||||
uint8_t _dummy;
|
uint8_t _dummy;
|
||||||
|
|
||||||
@ -465,6 +469,8 @@ public:
|
|||||||
#endif
|
#endif
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
rc_12 (CH_12),
|
rc_12 (CH_12),
|
||||||
|
rc_13 (CH_13),
|
||||||
|
rc_14 (CH_14),
|
||||||
#endif
|
#endif
|
||||||
_dummy(0)
|
_dummy(0)
|
||||||
{}
|
{}
|
||||||
|
@ -863,6 +863,14 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Group: RC12_
|
// @Group: RC12_
|
||||||
// @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_12, "RC12_", RC_Channel_aux),
|
GGROUP(rc_12, "RC12_", RC_Channel_aux),
|
||||||
|
|
||||||
|
// @Group: RC13_
|
||||||
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
|
GGROUP(rc_13, "RC13_", RC_Channel_aux),
|
||||||
|
|
||||||
|
// @Group: RC14_
|
||||||
|
// @Path: ../libraries/RC_Channel/RC_Channel.cpp,../libraries/RC_Channel/RC_Channel_aux.cpp
|
||||||
|
GGROUP(rc_14, "RC14_", RC_Channel_aux),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Group: RLL2SRV_
|
// @Group: RLL2SRV_
|
||||||
|
@ -65,6 +65,8 @@ static void init_rc_out()
|
|||||||
#endif
|
#endif
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
servo_write(CH_12, g.rc_12.radio_trim);
|
servo_write(CH_12, g.rc_12.radio_trim);
|
||||||
|
servo_write(CH_13, g.rc_13.radio_trim);
|
||||||
|
servo_write(CH_14, g.rc_14.radio_trim);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// setup PX4 to output the min throttle when safety off if arming
|
// setup PX4 to output the min throttle when safety off if arming
|
||||||
|
Loading…
Reference in New Issue
Block a user