Plane: make OVERRIDE_CHAN behaviour exactly match FLTMODE6

this provides a convenient "real manual" flight mode
This commit is contained in:
Andrew Tridgell 2014-11-06 17:41:25 +11:00
parent bfb2a7eb93
commit e30838a4ef
2 changed files with 2 additions and 2 deletions

View File

@ -877,7 +877,7 @@ const AP_Param::Info var_info[] PROGMEM = {
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// @Param: OVERRIDE_CHAN
// @DisplayName: PX4IO override channel
// @Description: If set to a non-zero value then this is an RC input channel number to use for testing manual control in case the main FMU microcontroller on a PX4 or Pixhawk fails. When this RC input channel goes above 1750 the FMU will stop sending servo controls to the PX4IO board, which will trigger the PX4IO board to start using its failsafe override behaviour, which should give you manual control of the aircraft. That allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is normally only set to a non-zero value for ground testing purposes. When the override channel is used it also forces the PX4 safety switch into an armed state. This allows it to be used as a way to re-arm a plane after an in-flight reboot. Use in that way is considered a developer option, for people testing unstable developer code.
// @Description: If set to a non-zero value then this is an RC input channel number to use for testing manual control in case the main FMU microcontroller on a PX4 or Pixhawk fails. When this RC input channel goes above 1750 the FMU will stop sending servo controls to the PX4IO board, which will trigger the PX4IO board to start using its failsafe override behaviour, which should give you manual control of the aircraft. That allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is normally only set to a non-zero value for ground testing purposes. When the override channel is used it also forces the PX4 safety switch into an armed state. This allows it to be used as a way to re-arm a plane after an in-flight reboot. Use in that way is considered a developer option, for people testing unstable developer code. Note that you may set OVERRIDE_CHAN to the same channel as FLTMODE_CH to get PX4IO based override when in flight mode 6.
// @User: Advanced
GSCALAR(override_channel, "OVERRIDE_CHAN", 0),
#endif

View File

@ -63,7 +63,7 @@ static void read_control_switch()
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
if (g.override_channel > 0) {
// if the user has configured an override channel then check it
bool override = (hal.rcin->read(g.override_channel-1) > PX4IO_OVERRIDE_PWM);
bool override = (hal.rcin->read(g.override_channel-1) >= PX4IO_OVERRIDE_PWM);
if (override && !px4io_override_enabled) {
if (setup_failsafe_mixing()) {
px4io_override_enabled = true;