Plane: trigger OVERRIDE_CHAN in px4io

setup the MODESWITCH channel as our OVERRIDE_CHAN, allowing for
instant manual passthru in px4io when OVERRIDE_CHAN goes above 1750

This makes for faster switching, and avoids bugs where a still enabled
FMU channel disables override
This commit is contained in:
Andrew Tridgell 2015-06-21 18:19:16 +10:00
parent f628440df9
commit 4aac2c5c96
4 changed files with 25 additions and 23 deletions

View File

@ -273,9 +273,7 @@ void Plane::obc_fs_check(void)
*/
void Plane::update_aux(void)
{
if (!px4io_override_enabled) {
RC_Channel_aux::enable_aux_servos();
}
RC_Channel_aux::enable_aux_servos();
}
void Plane::one_second_loop()

View File

@ -81,10 +81,6 @@ void Plane::read_control_switch()
}
} else if (!override && px4io_override_enabled) {
px4io_override_enabled = false;
// re-enable output channels
for (uint8_t i=0; i<8; i++) {
hal.rcout->enable_ch(i);
}
RC_Channel_aux::enable_aux_servos();
gcs_send_text_P(SEVERITY_LOW, PSTR("PX4IO Override disabled"));
}
@ -95,17 +91,6 @@ void Plane::read_control_switch()
// re-arm and take manual control
hal.rcout->force_safety_off();
}
if (px4io_override_enabled) {
/*
ensure that all channels are disabled from the FMU. If
PX4IO receives any channel input from the FMU then it
will think the FMU is still active and won't enable the
internal mixer.
*/
for (uint8_t i=0; i<16; i++) {
hal.rcout->disable_ch(i);
}
}
}
#endif // CONFIG_HAL_BOARD
}

View File

@ -20,6 +20,7 @@
#include <stdio.h>
#include <drivers/drv_pwm_output.h>
#include <systemlib/mixer/mixer.h>
#include <modules/px4iofirmware/protocol.h>
#define PX4_LIM_RC_MIN 900
#define PX4_LIM_RC_MAX 2100
@ -307,7 +308,7 @@ bool Plane::setup_failsafe_mixing(void)
config.rc_trim = constrain_int16(ch->radio_trim, config.rc_min+1, config.rc_max-1);
}
config.rc_dz = 0; // zero for the purposes of manual takeover
config.rc_assignment = i;
// we set reverse as false, as users of ArduPilot will have
// input reversed on transmitter, so from the point of view of
// the mixer the input is never reversed. The one exception is
@ -318,6 +319,25 @@ bool Plane::setup_failsafe_mixing(void)
} else {
config.rc_reverse = false;
}
if (i+1 == g.override_channel.get()) {
/*
This is an OVERRIDE_CHAN channel. We want IO to trigger
override with a channel input of over 1750. The px4io
code is setup for triggering below 10% of full range. To
map this to values above 1750 we need to reverse the
direction and set the rc range for this channel to 1000
to 1833 (1833 = 1000 + 750/0.9)
*/
config.rc_assignment = PX4IO_P_RC_CONFIG_ASSIGNMENT_MODESWITCH;
config.rc_reverse = true;
config.rc_max = 1833;
config.rc_min = 1000;
config.rc_trim = 1500;
} else {
config.rc_assignment = i;
}
if (ioctl(px4io_fd, PWM_SERVO_SET_RC_CONFIG, (unsigned long)&config) != 0) {
hal.console->printf("SET_RC_CONFIG failed\n");
goto failed;

View File

@ -751,10 +751,9 @@ bool Plane::arm_motors(AP_Arming::ArmingMethod method)
return false;
}
//only log if arming was successful
if (!px4io_override_enabled) {
channel_throttle->enable_out();
}
// only log if arming was successful
channel_throttle->enable_out();
change_arm_state();
return true;
}