Plane: enable mixer setup with ChibiOS fw

allows for pass-thu on FMU failure
This commit is contained in:
Andrew Tridgell 2019-07-10 21:56:13 +10:00
parent f8c5f7ca9c
commit bdf63b5420
3 changed files with 11 additions and 2 deletions

View File

@ -255,11 +255,20 @@ void Plane::afs_fs_check(void)
afs.check(failsafe.last_heartbeat_ms, geofence_breached(), failsafe.AFS_last_valid_rc_ms); afs.check(failsafe.last_heartbeat_ms, geofence_breached(), failsafe.AFS_last_valid_rc_ms);
} }
#if HAL_WITH_IO_MCU
#include <AP_IOMCU/AP_IOMCU.h>
extern AP_IOMCU iomcu;
#endif
void Plane::one_second_loop() void Plane::one_second_loop()
{ {
// send a heartbeat // send a heartbeat
gcs().send_message(MSG_HEARTBEAT); gcs().send_message(MSG_HEARTBEAT);
#if HAL_WITH_IO_MCU
iomcu.setup_mixing(&rcmap, g.override_channel.get(), g.mixing_gain, g2.manual_rc_mask);
#endif
// make it possible to change control channel ordering at runtime // make it possible to change control channel ordering at runtime
set_control_channels(); set_control_channels();

View File

@ -807,7 +807,7 @@ const AP_Param::Info Plane::var_info[] = {
// @User: Advanced // @User: Advanced
GSCALAR(flap_2_speed, "FLAP_2_SPEED", FLAP_2_SPEED), GSCALAR(flap_2_speed, "FLAP_2_SPEED", FLAP_2_SPEED),
#if HAVE_PX4_MIXER #if HAVE_PX4_MIXER || HAL_WITH_IO_MCU
// @Param: OVERRIDE_CHAN // @Param: OVERRIDE_CHAN
// @DisplayName: PX4IO override channel // @DisplayName: PX4IO override channel
// @Description: If set to a non-zero value then this is an RC input channel number to use for giving PX4IO manual control in case the main FMU microcontroller on a PX4 or Pixhawk fails. When this RC input channel goes above 1750 the FMU microcontroller will no longer be involved in controlling the servos and instead the PX4IO microcontroller will directly control the servos. Note that PX4IO manual control will be automatically activated if the FMU crashes for any reason. This parameter allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is can be set to a non-zero value either for ground testing purposes or for giving the effect of an external override control board. Please also see the docs on OVERRIDE_SAFETY. Note that you may set OVERRIDE_CHAN to the same channel as FLTMODE_CH to get PX4IO based override when in flight mode 6. Note that when override is triggered due to a FMU crash the 6 auxiliary output channels on Pixhawk will no longer be updated, so all the flight controls you need must be assigned to the first 8 channels. // @Description: If set to a non-zero value then this is an RC input channel number to use for giving PX4IO manual control in case the main FMU microcontroller on a PX4 or Pixhawk fails. When this RC input channel goes above 1750 the FMU microcontroller will no longer be involved in controlling the servos and instead the PX4IO microcontroller will directly control the servos. Note that PX4IO manual control will be automatically activated if the FMU crashes for any reason. This parameter allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is can be set to a non-zero value either for ground testing purposes or for giving the effect of an external override control board. Please also see the docs on OVERRIDE_SAFETY. Note that you may set OVERRIDE_CHAN to the same channel as FLTMODE_CH to get PX4IO based override when in flight mode 6. Note that when override is triggered due to a FMU crash the 6 auxiliary output channels on Pixhawk will no longer be updated, so all the flight controls you need must be assigned to the first 8 channels.

View File

@ -488,7 +488,7 @@ public:
AP_Int8 fbwa_tdrag_chan; AP_Int8 fbwa_tdrag_chan;
AP_Int8 rangefinder_landing; AP_Int8 rangefinder_landing;
AP_Int8 flap_slewrate; AP_Int8 flap_slewrate;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #if HAVE_PX4_MIXER || HAL_WITH_IO_MCU
AP_Int8 override_channel; AP_Int8 override_channel;
AP_Int8 override_safety; AP_Int8 override_safety;
#endif #endif