AP_Soaring: Use RC aux function rather than read RC directly.

This commit is contained in:
Samuel Tabor 2020-07-13 09:46:51 +01:00 committed by Andrew Tridgell
parent 455ebaadf2
commit 611217f63e
3 changed files with 10 additions and 24 deletions

View File

@ -135,6 +135,7 @@ void RC_Channel_Plane::init_aux_function(const RC_Channel::aux_func_t ch_option,
break;
case AUX_FUNC::Q_ASSIST:
case AUX_FUNC::SOARING:
do_aux_function(ch_option, ch_flag);
break;

View File

@ -114,12 +114,7 @@ const AP_Param::GroupInfo SoaringController::var_info[] = {
// @User: Advanced
AP_GROUPINFO("ALT_CUTOFF", 14, SoaringController, alt_cutoff, 250.0),
// @Param: ENABLE_CH
// @DisplayName: (Optional) RC channel that toggles the soaring controller on and off
// @Description: Toggles the soaring controller on and off. This parameter has any effect only if SOAR_ENABLE is set to 1 and this parameter is set to a valid non-zero channel number. When set, soaring will be activated when RC input to the specified channel is greater than or equal to 1700.
// @Range: 0 16
// @User: Advanced
AP_GROUPINFO("ENABLE_CH", 15, SoaringController, soar_active_ch, 0),
// 15 was SOAR_ENABLE_CH, now RCX_OPTION
// @Param: MAX_DRIFT
// @DisplayName: (Optional) Maximum drift distance to allow when thermalling.
@ -376,23 +371,10 @@ float SoaringController::McCready(float alt)
SoaringController::ActiveStatus SoaringController::active_state() const
{
if (!soar_active) {
return ActiveStatus::DISABLED;
}
if (soar_active_ch <= 0) {
// no activation channel
return ActiveStatus::AUTO_MODE_CHANGE;
return ActiveStatus::SOARING_DISABLED;
}
uint16_t radio_in = RC_Channels::get_radio_in(soar_active_ch-1);
// active when above 1400, with auto mode changes when above 1700
if (radio_in >= 1700) {
return ActiveStatus::AUTO_MODE_CHANGE;
} else if (radio_in >= 1400) {
return ActiveStatus::MANUAL_MODE_CHANGE;
}
return ActiveStatus::DISABLED;
return _pilot_desired_state;
}
void SoaringController::update_active_state()
@ -402,7 +384,7 @@ void SoaringController::update_active_state()
if (state_changed) {
switch (status) {
case ActiveStatus::DISABLED:
case ActiveStatus::SOARING_DISABLED:
// It's not enabled, but was enabled on the last loop.
gcs().send_text(MAV_SEVERITY_INFO, "Soaring: Disabled.");
set_throttle_suppressed(false);

View File

@ -56,7 +56,6 @@ class SoaringController {
protected:
AP_Int8 soar_active;
AP_Int8 soar_active_ch;
AP_Float thermal_vspeed;
AP_Float thermal_q1;
AP_Float thermal_q2;
@ -86,7 +85,7 @@ public:
};
enum class ActiveStatus {
DISABLED,
SOARING_DISABLED,
MANUAL_MODE_CHANGE,
AUTO_MODE_CHANGE
};
@ -123,11 +122,15 @@ public:
bool is_active() const {return _last_update_status>=SoaringController::ActiveStatus::MANUAL_MODE_CHANGE;};
void set_pilot_desired_state(ActiveStatus pilot_desired_state) {_pilot_desired_state = pilot_desired_state;};
private:
// slow down messages if they are the same. During loiter we could smap the same message. Only show new messages during loiters
LoiterStatus _cruise_criteria_msg_last;
ActiveStatus _last_update_status;
ActiveStatus _pilot_desired_state = ActiveStatus::AUTO_MODE_CHANGE;
ActiveStatus active_state() const;
};