mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: make Plane use more of RC_Channel library for mode switching
This commit is contained in:
parent
f6fa509443
commit
57d3ebf123
|
@ -63,7 +63,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
||||||
SCHED_TASK(check_short_failsafe, 50, 100, 9),
|
SCHED_TASK(check_short_failsafe, 50, 100, 9),
|
||||||
SCHED_TASK(update_speed_height, 50, 200, 12),
|
SCHED_TASK(update_speed_height, 50, 200, 12),
|
||||||
SCHED_TASK(update_throttle_hover, 100, 90, 24),
|
SCHED_TASK(update_throttle_hover, 100, 90, 24),
|
||||||
SCHED_TASK(read_control_switch, 7, 100, 27),
|
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&plane.g2.rc_channels, read_mode_switch, 7, 100, 27),
|
||||||
SCHED_TASK(update_GPS_50Hz, 50, 300, 30),
|
SCHED_TASK(update_GPS_50Hz, 50, 300, 30),
|
||||||
SCHED_TASK(update_GPS_10Hz, 10, 400, 33),
|
SCHED_TASK(update_GPS_10Hz, 10, 400, 33),
|
||||||
SCHED_TASK(navigate, 10, 150, 36),
|
SCHED_TASK(navigate, 10, 150, 36),
|
||||||
|
|
|
@ -190,6 +190,7 @@ private:
|
||||||
|
|
||||||
// flight modes convenience array
|
// flight modes convenience array
|
||||||
AP_Int8 *flight_modes = &g.flight_mode1;
|
AP_Int8 *flight_modes = &g.flight_mode1;
|
||||||
|
const uint8_t num_flight_modes = 6;
|
||||||
|
|
||||||
AP_FixedWing::Rangefinder_State rangefinder_state;
|
AP_FixedWing::Rangefinder_State rangefinder_state;
|
||||||
|
|
||||||
|
@ -966,7 +967,6 @@ private:
|
||||||
// control_modes.cpp
|
// control_modes.cpp
|
||||||
void read_control_switch();
|
void read_control_switch();
|
||||||
uint8_t readSwitch(void) const;
|
uint8_t readSwitch(void) const;
|
||||||
void reset_control_switch();
|
|
||||||
void autotune_start(void);
|
void autotune_start(void);
|
||||||
void autotune_restore(void);
|
void autotune_restore(void);
|
||||||
void autotune_enable(bool enable);
|
void autotune_enable(bool enable);
|
||||||
|
|
|
@ -45,8 +45,7 @@ void RC_Channel_Plane::do_aux_function_change_mode(const Mode::Number number,
|
||||||
// return to flight mode switch's flight mode if we are currently
|
// return to flight mode switch's flight mode if we are currently
|
||||||
// in this mode
|
// in this mode
|
||||||
if (plane.control_mode->mode_number() == number) {
|
if (plane.control_mode->mode_number() == number) {
|
||||||
// TODO: rc().reset_mode_switch();
|
rc().reset_mode_switch();
|
||||||
plane.reset_control_switch();
|
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -355,7 +354,7 @@ bool RC_Channel_Plane::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::MODE_SWITCH_RESET:
|
case AUX_FUNC::MODE_SWITCH_RESET:
|
||||||
plane.reset_control_switch();
|
rc().reset_mode_switch();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUX_FUNC::CRUISE:
|
case AUX_FUNC::CRUISE:
|
||||||
|
|
|
@ -13,6 +13,9 @@ protected:
|
||||||
AuxSwitchPos ch_flag) override;
|
AuxSwitchPos ch_flag) override;
|
||||||
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
|
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
|
||||||
|
|
||||||
|
// called when the mode switch changes position:
|
||||||
|
void mode_switch_changed(modeswitch_pos_t new_pos) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
void do_aux_function_change_mode(Mode::Number number,
|
void do_aux_function_change_mode(Mode::Number number,
|
||||||
|
@ -46,6 +49,8 @@ public:
|
||||||
|
|
||||||
RC_Channel *get_arming_channel(void) const override;
|
RC_Channel *get_arming_channel(void) const override;
|
||||||
|
|
||||||
|
void read_mode_switch() override;
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
// note that these callbacks are not presently used on Plane:
|
// note that these callbacks are not presently used on Plane:
|
||||||
|
|
|
@ -98,61 +98,23 @@ Mode *Plane::mode_from_mode_num(const enum Mode::Number num)
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Plane::read_control_switch()
|
void RC_Channels_Plane::read_mode_switch()
|
||||||
{
|
{
|
||||||
static bool switch_debouncer;
|
if (millis() - plane.failsafe.last_valid_rc_ms > 100) {
|
||||||
uint8_t switchPosition = readSwitch();
|
|
||||||
|
|
||||||
// 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 (!rc().has_valid_input()) {
|
|
||||||
// ignore the mode switch channel if there is no valid RC input
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (millis() - failsafe.last_valid_rc_ms > 100) {
|
|
||||||
// only use signals that are less than 0.1s old.
|
// only use signals that are less than 0.1s old.
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
RC_Channels::read_mode_switch();
|
||||||
|
}
|
||||||
|
|
||||||
if (oldSwitchPosition != switchPosition) {
|
void RC_Channel_Plane::mode_switch_changed(modeswitch_pos_t new_pos)
|
||||||
|
{
|
||||||
if (switch_debouncer == false) {
|
if (new_pos < 0 || (uint8_t)new_pos > plane.num_flight_modes) {
|
||||||
// this ensures that mode switches only happen if the
|
// should not have been called
|
||||||
// switch changes for 2 reads. This prevents momentary
|
return;
|
||||||
// spikes in the mode control channel from causing a mode
|
|
||||||
// switch
|
|
||||||
switch_debouncer = true;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
set_mode_by_number((enum Mode::Number)flight_modes[switchPosition].get(), ModeReason::RC_COMMAND);
|
|
||||||
|
|
||||||
oldSwitchPosition = switchPosition;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
switch_debouncer = false;
|
plane.set_mode_by_number((Mode::Number)plane.flight_modes[new_pos].get(), ModeReason::RC_COMMAND);
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t Plane::readSwitch(void) const
|
|
||||||
{
|
|
||||||
uint16_t pulsewidth = RC_Channels::get_radio_in(g.flight_mode_channel - 1);
|
|
||||||
if (pulsewidth <= 900 || pulsewidth >= 2200) return 255; // This is an error condition
|
|
||||||
if (pulsewidth <= 1230) return 0;
|
|
||||||
if (pulsewidth <= 1360) return 1;
|
|
||||||
if (pulsewidth <= 1490) return 2;
|
|
||||||
if (pulsewidth <= 1620) return 3;
|
|
||||||
if (pulsewidth <= 1749) return 4; // Software Manual
|
|
||||||
return 5; // Hardware Manual
|
|
||||||
}
|
|
||||||
|
|
||||||
void Plane::reset_control_switch()
|
|
||||||
{
|
|
||||||
oldSwitchPosition = 254;
|
|
||||||
read_control_switch();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
|
|
@ -142,7 +142,7 @@ void Plane::init_ardupilot()
|
||||||
|
|
||||||
// set the correct flight mode
|
// set the correct flight mode
|
||||||
// ---------------------------
|
// ---------------------------
|
||||||
reset_control_switch();
|
rc().reset_mode_switch();
|
||||||
|
|
||||||
// initialise sensor
|
// initialise sensor
|
||||||
#if AP_OPTICALFLOW_ENABLED
|
#if AP_OPTICALFLOW_ENABLED
|
||||||
|
|
Loading…
Reference in New Issue