Plane: added OVERRIDE_CHAN parameter

this allows both for testing PX4IO override on the ground, and for
forced manual override while flying, including re-arming after in-air
reboot
This commit is contained in:
Andrew Tridgell 2014-11-06 17:27:26 +11:00
parent c494057c98
commit 913004beb0
5 changed files with 61 additions and 1 deletions

View File

@ -350,6 +350,11 @@ static uint8_t oldSwitchPosition = 254;
// This is used to enable the inverted flight feature
static bool inverted_flight = false;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
// This is used to enable the PX4IO override for testing
static bool px4io_override_enabled = false;
#endif
static struct {
// These are trim values used for elevon control
// For elevons radio_in[CH_ROLL] and radio_in[CH_PITCH] are
@ -1006,7 +1011,9 @@ static void obc_fs_check(void)
*/
static void update_aux(void)
{
RC_Channel_aux::enable_aux_servos();
if (!px4io_override_enabled) {
RC_Channel_aux::enable_aux_servos();
}
#if MOUNT == ENABLED
camera_mount.update_mount_type();

View File

@ -128,6 +128,7 @@ public:
k_param_takeoff_flap_percent,
k_param_flap_slewrate,
k_param_rtl_autoland,
k_param_override_channel,
// 100: Arming parameters
k_param_arming = 100,
@ -469,6 +470,9 @@ public:
AP_Int8 fbwa_tdrag_chan;
AP_Int8 rangefinder_landing;
AP_Int8 flap_slewrate;
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
AP_Int8 override_channel;
#endif
// RC channels
RC_Channel rc_1;

View File

@ -874,6 +874,14 @@ const AP_Param::Info var_info[] PROGMEM = {
// @User: Advanced
GSCALAR(land_flap_percent, "LAND_FLAP_PERCNT", 0),
#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.
// @User: Advanced
GSCALAR(override_channel, "OVERRIDE_CHAN", 0),
#endif
// @Param: RSSI_PIN
// @DisplayName: Receiver RSSI sensing pin
// @Description: This selects an analog pin for the receiver RSSI voltage. It assumes the voltage is 5V for max rssi, 0V for minimum

View File

@ -445,6 +445,10 @@
# define INVERTED_FLIGHT_PWM 1750
#endif
#ifndef PX4IO_OVERRIDE_PWM
# define PX4IO_OVERRIDE_PWM 1750
#endif
//////////////////////////////////////////////////////////////////////////////
// Developer Items
//

View File

@ -59,6 +59,43 @@ static void read_control_switch()
// fly upside down when that channel goes above INVERTED_FLIGHT_PWM
inverted_flight = (control_mode != MANUAL && hal.rcin->read(g.inverted_flight_ch-1) > INVERTED_FLIGHT_PWM);
}
#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);
if (override && !px4io_override_enabled) {
if (setup_failsafe_mixing()) {
px4io_override_enabled = true;
// disable output channels to force PX4IO override
for (uint8_t i=0; i<16; i++) {
hal.rcout->disable_ch(i);
}
gcs_send_text_P(SEVERITY_LOW, PSTR("PX4IO Override enabled"));
} else {
// we'll try again next loop. The PX4IO code sometimes
// rejects a mixer, probably due to it being busy in
// some way?
gcs_send_text_P(SEVERITY_LOW, PSTR("PX4IO Override enable failed"));
}
} 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"));
}
if (px4io_override_enabled &&
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED) {
// we force safety off, so that if this override is used
// with a in-flight reboot it gives a way for the pilot to
// re-arm and take manual control
hal.rcout->force_safety_off();
}
}
#endif // CONFIG_HAL_BOARD
}
static uint8_t readSwitch(void)