Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: ICE: fully move to aux function #28655

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 6 additions & 3 deletions ArduCopter/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ void RC_Channel_Copter::init_aux_function(const AUX_FUNC ch_option, const AuxSwi
case AUX_FUNC::CUSTOM_CONTROLLER:
case AUX_FUNC::WEATHER_VANE_ENABLE:
case AUX_FUNC::TRANSMITTER_TUNING:
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT);
break;
default:
RC_Channel::init_aux_function(ch_option, ch_flag);
Expand Down Expand Up @@ -169,8 +169,11 @@ void RC_Channel_Copter::do_aux_function_change_mode(const Mode::Number mode,
}

// do_aux_function - implement the function invoked by auxiliary switches
bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Copter::do_aux_function(const AuxFuncTrigger &trigger)
{
const AUX_FUNC &ch_option = trigger.func;
const AuxSwitchPos &ch_flag = trigger.pos;

switch(ch_option) {
case AUX_FUNC::FLIP:
// flip if switch is on, positive throttle and we're actually flying
Expand Down Expand Up @@ -668,7 +671,7 @@ bool RC_Channel_Copter::do_aux_function(const AUX_FUNC ch_option, const AuxSwitc
break;

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
return RC_Channel::do_aux_function(trigger);
}
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion ArduCopter/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ class RC_Channel_Copter : public RC_Channel
protected:

void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(const AuxFuncTrigger &trigger) override;

private:

Expand Down
24 changes: 15 additions & 9 deletions ArduPlane/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -172,9 +172,6 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
case AUX_FUNC::FW_AUTOTUNE:
case AUX_FUNC::VFWD_THR_OVERRIDE:
case AUX_FUNC::PRECISION_LOITER:
#if AP_ICENGINE_ENABLED
case AUX_FUNC::ICE_START_STOP:
#endif
#if QAUTOTUNE_ENABLED
case AUX_FUNC::AUTOTUNE_TEST_GAINS:
#endif
Expand All @@ -194,7 +191,10 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
#endif
case AUX_FUNC::TER_DISABLE:
case AUX_FUNC::CROW_SELECT:
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
#if AP_ICENGINE_ENABLED
case AUX_FUNC::ICE_START_STOP:
#endif
run_aux_function(ch_option, ch_flag, AuxFuncTrigger::Source::INIT);
break;

case AUX_FUNC::REVERSE_THROTTLE:
Expand All @@ -216,8 +216,11 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::AUX_FUNC ch_option,
}

// do_aux_function - implement the function invoked by auxiliary switches
bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Plane::do_aux_function(const AuxFuncTrigger &trigger)
{
const AUX_FUNC &ch_option = trigger.func;
const AuxSwitchPos &ch_flag = trigger.pos;

switch(ch_option) {
case AUX_FUNC::INVERTED:
plane.inverted_flight = (ch_flag == AuxSwitchPos::HIGH);
Expand Down Expand Up @@ -296,9 +299,6 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
case AUX_FUNC::FLAP:
case AUX_FUNC::FBWA_TAILDRAGGER:
case AUX_FUNC::AIRBRAKE:
#if AP_ICENGINE_ENABLED
case AUX_FUNC::ICE_START_STOP:
#endif
break; // input labels, nothing to do

#if HAL_QUADPLANE_ENABLED
Expand Down Expand Up @@ -468,8 +468,14 @@ bool RC_Channel_Plane::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break;
#endif

#if AP_ICENGINE_ENABLED
case AUX_FUNC::ICE_START_STOP:
plane.g2.ice_control.do_aux_function(trigger);
break;
#endif

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
return RC_Channel::do_aux_function(trigger);
}

return true;
Expand Down
2 changes: 1 addition & 1 deletion ArduPlane/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@ class RC_Channel_Plane : public RC_Channel

void init_aux_function(AUX_FUNC ch_option,
AuxSwitchPos ch_flag) override;
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(const AuxFuncTrigger &trigger) override;

// called when the mode switch changes position:
void mode_switch_changed(modeswitch_pos_t new_pos) override;
Expand Down
7 changes: 5 additions & 2 deletions Blimp/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -99,8 +99,11 @@ void RC_Channel_Blimp::do_aux_function_change_mode(const Mode::Number mode,
}

// do_aux_function - implement the function invoked by auxiliary switches
bool RC_Channel_Blimp::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Blimp::do_aux_function(const AuxFuncTrigger &trigger)
{
const AUX_FUNC &ch_option = trigger.func;
const AuxSwitchPos &ch_flag = trigger.pos;

switch (ch_option) {

case AUX_FUNC::SAVE_TRIM:
Expand All @@ -120,7 +123,7 @@ bool RC_Channel_Blimp::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break;

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
return RC_Channel::do_aux_function(trigger);
}
return true;
}
Expand Down
2 changes: 1 addition & 1 deletion Blimp/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ class RC_Channel_Blimp : public RC_Channel
protected:

void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(const AuxFuncTrigger &trigger) override;

private:

Expand Down
7 changes: 5 additions & 2 deletions Rover/RC_Channel.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,8 +130,11 @@ void RC_Channel_Rover::do_aux_function_sailboat_motor_3pos(const AuxSwitchPos ch
}
}

bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitchPos ch_flag)
bool RC_Channel_Rover::do_aux_function(const AuxFuncTrigger &trigger)
{
const AUX_FUNC &ch_option = trigger.func;
const AuxSwitchPos &ch_flag = trigger.pos;

switch (ch_option) {
case AUX_FUNC::DO_NOTHING:
break;
Expand Down Expand Up @@ -261,7 +264,7 @@ bool RC_Channel_Rover::do_aux_function(const AUX_FUNC ch_option, const AuxSwitch
break;

default:
return RC_Channel::do_aux_function(ch_option, ch_flag);
return RC_Channel::do_aux_function(trigger);

}

Expand Down
2 changes: 1 addition & 1 deletion Rover/RC_Channel.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ class RC_Channel_Rover : public RC_Channel
protected:

void init_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(AUX_FUNC ch_option, AuxSwitchPos) override;
bool do_aux_function(const AuxFuncTrigger &trigger) override;

// called when the mode switch changes position:
void mode_switch_changed(modeswitch_pos_t new_pos) override;
Expand Down
1 change: 1 addition & 0 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1234,6 +1234,7 @@ def MAV_CMD_DO_ENGINE_CONTROL(self):
self.start_subtest("Check start chan control disable")
old_start_channel_value = self.get_rc_channel_value(rc_engine_start_chan)
self.set_rc(rc_engine_start_chan, 1000)
self.delay_sim_time(1) # Make sure the RC change has registered
self.context_collect('STATUSTEXT')
method(mavutil.mavlink.MAV_CMD_DO_ENGINE_CONTROL, p1=1, want_result=mavutil.mavlink.MAV_RESULT_FAILED)
self.wait_statustext("start control disabled", check_context=True)
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Button/AP_Button.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -278,7 +278,7 @@ void AP_Button::run_aux_functions(bool force)
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Button %i: executing (%s %s)", i+1, str, rc_channel->string_for_aux_pos(pos));
}
#endif
rc_channel->run_aux_function(func, pos, RC_Channel::AuxFuncTriggerSource::BUTTON);
rc_channel->run_aux_function(func, pos, RC_Channel::AuxFuncTrigger::Source::BUTTON);
}
}

Expand Down
64 changes: 20 additions & 44 deletions libraries/AP_ICEngine/AP_ICEngine.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,6 @@

extern const AP_HAL::HAL& hal;

#define AP_ICENGINE_START_CHAN_DEBOUNCE_MS 300

const AP_Param::GroupInfo AP_ICEngine::var_info[] = {

// @Param: ENABLE
Expand Down Expand Up @@ -282,6 +280,17 @@ void AP_ICEngine::param_conversion()
}
}

// Handle incoming aux function
void AP_ICEngine::do_aux_function(const RC_Channel::AuxFuncTrigger &trigger)
{
// If triggered from RC apply start chan min
if ((trigger.source == RC_Channel::AuxFuncTrigger::Source::RC) && (trigger.pwm < start_chan_min_pwm)) {
return;
}

aux_pos = trigger.pos;
}

/*
update engine state
*/
Expand All @@ -291,51 +300,20 @@ void AP_ICEngine::update(void)
return;
}

uint16_t cvalue = 1500;
RC_Channel *c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ICE_START_STOP);
if (c != nullptr && rc().has_valid_input()) {
// get starter control channel
cvalue = c->get_radio_in();

if (cvalue < start_chan_min_pwm) {
cvalue = start_chan_last_value;
}

// snap the input to either 1000, 1500, or 2000
// this is useful to compare a debounce changed value
// while ignoring tiny noise
if (cvalue >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
cvalue = 2000;
} else if ((cvalue > 800) && (cvalue <= RC_Channel::AUX_PWM_TRIGGER_LOW)) {
cvalue = 1300;
} else {
cvalue = 1500;
}
}

bool should_run = false;
uint32_t now = AP_HAL::millis();


// debounce timer to protect from spurious changes on start_chan rc input
// If the cached value is the same, reset timer
if (start_chan_last_value == cvalue) {
start_chan_last_ms = now;
} else if (now - start_chan_last_ms >= AP_ICENGINE_START_CHAN_DEBOUNCE_MS) {
// if it has changed, and stayed changed for the duration, then use that new value
start_chan_last_value = cvalue;
}

if (state == ICE_START_HEIGHT_DELAY && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
if ((state == ICE_START_HEIGHT_DELAY) && (aux_pos == RC_Channel::AuxSwitchPos::HIGH)) {
Comment on lines -294 to +307
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a really nice cleanup!

// user is overriding the height start delay and asking for
// immediate start. Put into ICE_OFF so that the logic below
// can start the engine now
state = ICE_OFF;
}

if (state == ICE_OFF && start_chan_last_value >= RC_Channel::AUX_PWM_TRIGGER_HIGH) {
if ((state == ICE_OFF) && (aux_pos == RC_Channel::AuxSwitchPos::HIGH)) {
should_run = true;
} else if (start_chan_last_value <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
} else if (aux_pos == RC_Channel::AuxSwitchPos::LOW) {
should_run = false;

// clear the single start flag now that we will be stopping the engine
Expand Down Expand Up @@ -622,15 +600,13 @@ bool AP_ICEngine::engine_control(float start_control, float cold_start, float he
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: already running");
return false;
}
RC_Channel *c = rc().find_channel_for_option(RC_Channel::AUX_FUNC::ICE_START_STOP);
if (c != nullptr && rc().has_valid_input()) {
// get starter control channel
uint16_t cvalue = c->get_radio_in();
if (cvalue >= start_chan_min_pwm && cvalue <= RC_Channel::AUX_PWM_TRIGGER_LOW) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: start control disabled");
return false;
}

// get starter control channel
if (aux_pos == RC_Channel::AuxSwitchPos::LOW) {
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Engine: start control disabled by aux function");
return false;
}

if (height_delay > 0) {
height_pending = true;
initial_height = 0;
Expand Down
11 changes: 7 additions & 4 deletions libraries/AP_ICEngine/AP_ICEngine.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
#include <AP_RPM/AP_RPM_config.h>
#include <AP_HAL/I2CDevice.h>
#include <AP_Relay/AP_Relay_config.h>
#include <RC_Channel/RC_Channel.h>

#if AP_ICENGINE_TCA9554_STARTER_ENABLED
#include "AP_ICEngine_TCA9554.h"
Expand Down Expand Up @@ -69,6 +70,9 @@ class AP_ICEngine {
// do we have throttle while disarmed enabled?
bool allow_throttle_while_disarmed(void) const;

// Handle incoming aux function trigger
void do_aux_function(const RC_Channel::AuxFuncTrigger &trigger);

#if AP_RELAY_ENABLED
// Needed for param conversion from relay numbers to functions
bool get_legacy_ignition_relay_index(int8_t &num);
Expand All @@ -95,7 +99,7 @@ class AP_ICEngine {

// min pwm on start channel for engine stop
AP_Int16 start_chan_min_pwm;

#if AP_RPM_ENABLED
// which RPM instance to use
AP_Int8 rpm_instance;
Expand Down Expand Up @@ -169,9 +173,8 @@ class AP_ICEngine {
return (options & uint16_t(option)) != 0;
}

// start_chan debounce
uint16_t start_chan_last_value = 1500;
uint32_t start_chan_last_ms;
// Last aux function value
RC_Channel::AuxSwitchPos aux_pos = RC_Channel::AuxSwitchPos::MIDDLE;

#if AP_ICENGINE_TCA9554_STARTER_ENABLED
AP_ICEngine_TCA9554 tca9554_starter;
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Mission/AP_Mission_Commands.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ bool AP_Mission::start_command_do_aux_function(const AP_Mission::Mission_Command
default:
return false;
}
rc().run_aux_function(function, pos, RC_Channel::AuxFuncTriggerSource::MISSION);
rc().run_aux_function(function, pos, RC_Channel::AuxFuncTrigger::Source::MISSION);
return true;
}
#endif // AP_RC_CHANNEL_ENABLED
Expand Down
2 changes: 1 addition & 1 deletion libraries/AP_Scripting/generator/description/bindings.desc
Original file line number Diff line number Diff line change
Expand Up @@ -398,7 +398,7 @@ singleton RC_Channels rename rc
singleton RC_Channels scheduler-semaphore
singleton RC_Channels method get_pwm boolean uint8_t 1 NUM_RC_CHANNELS uint16_t'Null
singleton RC_Channels method find_channel_for_option RC_Channel RC_Channel::AUX_FUNC'enum 0 UINT16_MAX
singleton RC_Channels method run_aux_function boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX RC_Channel::AuxSwitchPos'enum RC_Channel::AuxSwitchPos::LOW RC_Channel::AuxSwitchPos::HIGH RC_Channel::AuxFuncTriggerSource::SCRIPTING'literal
singleton RC_Channels method run_aux_function boolean RC_Channel::AUX_FUNC'enum 0 UINT16_MAX RC_Channel::AuxSwitchPos'enum RC_Channel::AuxSwitchPos::LOW RC_Channel::AuxSwitchPos::HIGH RC_Channel::AuxFuncTrigger::Source::SCRIPTING'literal
singleton RC_Channels method has_valid_input boolean
singleton RC_Channels method lua_rc_channel RC_Channel uint8_t 1 NUM_RC_CHANNELS
singleton RC_Channels method lua_rc_channel rename get_channel
Expand Down
2 changes: 1 addition & 1 deletion libraries/GCS_MAVLink/GCS_Common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -3110,7 +3110,7 @@ MAV_RESULT GCS_MAVLINK::handle_command_do_aux_function(const mavlink_command_int
}
const RC_Channel::AUX_FUNC aux_func = (RC_Channel::AUX_FUNC)packet.param1;
const RC_Channel::AuxSwitchPos position = (RC_Channel::AuxSwitchPos)packet.param2;
if (!rc().run_aux_function(aux_func, position, RC_Channel::AuxFuncTriggerSource::MAVLINK)) {
if (!rc().run_aux_function(aux_func, position, RC_Channel::AuxFuncTrigger::Source::MAVLINK)) {
// note that this is not quite right; we could be more nuanced
// about our return code here.
return MAV_RESULT_FAILED;
Expand Down
Loading
Loading