ardupilot/ArduPlane/control_modes.cpp

166 lines
5.5 KiB
C++
Raw Normal View History

/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
2015-05-13 03:09:36 -03:00
#include "Plane.h"
2015-05-13 03:09:36 -03:00
void Plane::read_control_switch()
{
2012-08-16 21:50:15 -03:00
static bool switch_debouncer;
2012-12-04 18:22:21 -04:00
uint8_t switchPosition = readSwitch();
2012-08-16 21:50:15 -03:00
// If switchPosition = 255 this indicates that the mode control channel input was out of range
// If we get this value we do not want to change modes.
if(switchPosition == 255) return;
if (failsafe.ch3_failsafe || failsafe.ch3_counter > 0) {
// when we are in ch3_failsafe mode then RC input is not
// working, and we need to ignore the mode switch channel
return;
}
if (millis() - failsafe.last_valid_rc_ms > 100) {
// only use signals that are less than 0.1s old.
return;
}
// we look for changes in the switch position. If the
// RST_SWITCH_CH parameter is set, then it is a switch that can be
// used to force re-reading of the control switch. This is useful
// when returning to the previous mode after a failsafe or fence
// breach. This channel is best used on a momentary switch (such
// as a spring loaded trainer switch).
2012-08-16 21:50:15 -03:00
if (oldSwitchPosition != switchPosition ||
(g.reset_switch_chan != 0 &&
2012-12-04 18:22:21 -04:00
hal.rcin->read(g.reset_switch_chan-1) > RESET_SWITCH_CHAN_PWM)) {
if (switch_debouncer == false) {
// this ensures that mode switches only happen if the
// switch changes for 2 reads. This prevents momentary
// spikes in the mode control channel from causing a mode
// switch
switch_debouncer = true;
return;
}
set_mode((enum FlightMode)(flight_modes[switchPosition].get()));
2012-08-16 21:50:15 -03:00
oldSwitchPosition = switchPosition;
}
2012-08-16 21:50:15 -03:00
if (g.reset_mission_chan != 0 &&
2012-12-04 18:22:21 -04:00
hal.rcin->read(g.reset_mission_chan-1) > RESET_SWITCH_CHAN_PWM) {
mission.start();
prev_WP_loc = current_loc;
}
switch_debouncer = false;
if (g.inverted_flight_ch != 0) {
// if the user has configured an inverted flight channel, then
// fly upside down when that channel goes above INVERTED_FLIGHT_PWM
2012-12-04 18:22:21 -04:00
inverted_flight = (control_mode != MANUAL && hal.rcin->read(g.inverted_flight_ch-1) > INVERTED_FLIGHT_PWM);
}
if (g.parachute_channel > 0) {
if (hal.rcin->read(g.parachute_channel-1) >= 1700) {
parachute_manual_release();
}
}
#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) {
// we only update the mixer if we are not armed. This is
// important as otherwise we will need to temporarily
// disarm to change the mixer
2015-01-28 19:30:00 -04:00
if (hal.util->get_soft_armed() || setup_failsafe_mixing()) {
px4io_override_enabled = true;
// disable output channels to force PX4IO override
2015-11-18 15:17:50 -04:00
gcs_send_text(MAV_SEVERITY_WARNING, "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?
2015-11-18 15:17:50 -04:00
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO override enable failed");
}
} else if (!override && px4io_override_enabled) {
px4io_override_enabled = false;
RC_Channel_aux::enable_aux_servos();
2015-11-18 15:17:50 -04:00
gcs_send_text(MAV_SEVERITY_WARNING, "PX4IO override disabled");
}
if (px4io_override_enabled &&
2016-01-28 01:37:50 -04:00
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_ARMED &&
g.override_safety == 1) {
// 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
}
2015-05-13 03:09:36 -03:00
uint8_t Plane::readSwitch(void)
{
2012-12-04 18:22:21 -04:00
uint16_t pulsewidth = hal.rcin->read(g.flight_mode_channel - 1);
if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition
2012-08-16 21:50:15 -03:00
if (pulsewidth > 1230 && pulsewidth <= 1360) return 1;
if (pulsewidth > 1360 && pulsewidth <= 1490) return 2;
if (pulsewidth > 1490 && pulsewidth <= 1620) return 3;
if (pulsewidth > 1620 && pulsewidth <= 1749) return 4; // Software Manual
if (pulsewidth >= 1750) return 5; // Hardware Manual
return 0;
}
2015-05-13 03:09:36 -03:00
void Plane::reset_control_switch()
{
oldSwitchPosition = 254;
2012-08-16 21:50:15 -03:00
read_control_switch();
}
/*
called when entering autotune
*/
2015-05-13 03:09:36 -03:00
void Plane::autotune_start(void)
{
rollController.autotune_start();
pitchController.autotune_start();
}
/*
called when exiting autotune
*/
2015-05-13 03:09:36 -03:00
void Plane::autotune_restore(void)
{
rollController.autotune_restore();
pitchController.autotune_restore();
}
/*
enable/disable autotune for AUTO modes
*/
void Plane::autotune_enable(bool enable)
{
if (enable) {
autotune_start();
} else {
autotune_restore();
}
}
/*
are we flying inverted?
*/
2015-05-13 03:09:36 -03:00
bool Plane::fly_inverted(void)
{
if (g.inverted_flight_ch != 0 && inverted_flight) {
// controlled with INVERTED_FLIGHT_CH
return true;
}
if (control_mode == AUTO && auto_state.inverted_flight) {
return true;
}
return false;
}