diff --git a/src/modules/sensors/sensor_params.c b/src/modules/sensors/sensor_params.c
index a34f819235..48e5d80e73 100644
--- a/src/modules/sensors/sensor_params.c
+++ b/src/modules/sensors/sensor_params.c
@@ -684,3 +684,83 @@ PARAM_DEFINE_INT32(RC_MAP_AUX3, 0);
* @group Radio Calibration
*/
PARAM_DEFINE_INT32(RC_FAILS_THR, 0);
+
+/**
+ * Threshold for selecting assisted mode
+ *
+ * min:-1
+ * max:+1
+ *
+ * 0-1 indicate where in the full channel range the threshold sits
+ * 0 : min
+ * 1 : max
+ * sign indicates polarity of comparison
+ * positive : true when channel>th
+ * negative : true when channel
th
+ * negative : true when channel | th
+ * negative : true when channel | th
+ * negative : true when channel | th
+ * negative : true when channel | = 0) {
- float value = _rc.chan[_rc.function[func]].scaled;
- if (value > STICK_ON_OFF_LIMIT) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+ if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
- } else if (value < -STICK_ON_OFF_LIMIT) {
- return SWITCH_POS_OFF;
+ } else if (mid_inv ? value < mid_th : value > mid_th) {
+ return SWITCH_POS_MIDDLE;
} else {
- return SWITCH_POS_MIDDLE;
+ return SWITCH_POS_OFF;
}
} else {
@@ -1303,11 +1338,11 @@ Sensors::get_rc_sw3pos_position(enum RC_CHANNELS_FUNCTION func)
}
switch_pos_t
-Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func)
+Sensors::get_rc_sw2pos_position(enum RC_CHANNELS_FUNCTION func, float on_th, bool on_inv)
{
if (_rc.function[func] >= 0) {
- float value = _rc.chan[_rc.function[func]].scaled;
- if (value > STICK_ON_OFF_LIMIT) {
+ float value = 0.5f * _rc.chan[_rc.function[func]].scaled + 0.5f;
+ if (on_inv ? value < on_th : value > on_th) {
return SWITCH_POS_ON;
} else {
@@ -1345,10 +1380,10 @@ Sensors::rc_poll()
/* check failsafe */
int8_t fs_ch = _rc.function[_parameters.rc_map_failsafe];
- if (_parameters.rc_fs_thr > 0 && fs_ch >= 0) {
+ if (_parameters.rc_fails_thr > 0 && fs_ch >= 0) {
/* failsafe configured */
- if ((_parameters.rc_fs_thr < _parameters.min[fs_ch] && rc_input.values[fs_ch] < _parameters.rc_fs_thr) ||
- (_parameters.rc_fs_thr > _parameters.max[fs_ch] && rc_input.values[fs_ch] > _parameters.rc_fs_thr)) {
+ if ((_parameters.rc_fails_thr < _parameters.min[fs_ch] && rc_input.values[fs_ch] < _parameters.rc_fails_thr) ||
+ (_parameters.rc_fails_thr > _parameters.max[fs_ch] && rc_input.values[fs_ch] > _parameters.rc_fails_thr)) {
/* failsafe triggered, signal is lost by receiver */
signal_lost = true;
}
@@ -1439,10 +1474,10 @@ Sensors::rc_poll()
manual.aux5 = get_rc_value(AUX_5, -1.0, 1.0);
/* mode switches */
- manual.mode_switch = get_rc_sw3pos_position(MODE);
- manual.easy_switch = get_rc_sw2pos_position(EASY);
- manual.loiter_switch = get_rc_sw2pos_position(LOITER);
- manual.return_switch = get_rc_sw2pos_position(RETURN);
+ manual.mode_switch = get_rc_sw3pos_position(MODE, _parameters.rc_auto_th, _parameters.rc_auto_inv, _parameters.rc_assisted_th, _parameters.rc_assisted_inv);
+ manual.easy_switch = get_rc_sw2pos_position(EASY, _parameters.rc_easy_th, _parameters.rc_easy_inv);
+ manual.return_switch = get_rc_sw2pos_position(RETURN, _parameters.rc_return_th, _parameters.rc_return_inv);
+ manual.loiter_switch = get_rc_sw2pos_position(LOITER, _parameters.rc_loiter_th, _parameters.rc_loiter_inv);
/* publish manual_control_setpoint topic */
if (_manual_control_pub > 0) {
|