2013-08-29 02:34:34 -03:00
|
|
|
/*
|
|
|
|
This program is free software: you can redistribute it and/or modify
|
|
|
|
it under the terms of the GNU General Public License as published by
|
|
|
|
the Free Software Foundation, either version 3 of the License, or
|
|
|
|
(at your option) any later version.
|
|
|
|
|
|
|
|
This program is distributed in the hope that it will be useful,
|
|
|
|
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
|
|
GNU General Public License for more details.
|
|
|
|
|
|
|
|
You should have received a copy of the GNU General Public License
|
|
|
|
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
|
2010-11-23 15:28:19 -04:00
|
|
|
/*
|
2017-02-05 22:15:33 -04:00
|
|
|
* RC_Channel.cpp - class for one RC channel input
|
2012-08-17 03:22:48 -03:00
|
|
|
*/
|
2010-11-23 15:28:19 -04:00
|
|
|
|
2012-10-26 20:59:16 -03:00
|
|
|
#include <stdlib.h>
|
2016-03-31 18:43:36 -03:00
|
|
|
#include <cmath>
|
2012-10-26 20:59:16 -03:00
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2012-10-26 20:59:16 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2015-08-11 03:28:46 -03:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2012-10-26 20:59:16 -03:00
|
|
|
|
2010-11-23 15:28:19 -04:00
|
|
|
#include "RC_Channel.h"
|
2018-04-13 23:22:14 -03:00
|
|
|
#include <GCS_MAVLink/GCS.h>
|
|
|
|
|
2018-10-25 04:36:20 -03:00
|
|
|
#include <AC_Avoidance/AC_Avoid.h>
|
2018-06-08 00:37:51 -03:00
|
|
|
#include <AC_Sprayer/AC_Sprayer.h>
|
2019-04-04 08:08:20 -03:00
|
|
|
#include <AP_Camera/AP_Camera.h>
|
2019-11-13 19:50:45 -04:00
|
|
|
#include <AP_Camera/AP_RunCam.h>
|
2020-10-22 14:14:53 -03:00
|
|
|
#include <AP_Generator/AP_Generator.h>
|
2018-06-08 00:37:51 -03:00
|
|
|
#include <AP_Gripper/AP_Gripper.h>
|
2019-11-03 20:18:01 -04:00
|
|
|
#include <AP_ADSB/AP_ADSB.h>
|
2018-11-08 20:02:54 -04:00
|
|
|
#include <AP_LandingGear/AP_LandingGear.h>
|
2022-03-03 23:29:48 -04:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2019-04-04 08:08:20 -03:00
|
|
|
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
|
2019-05-03 08:26:28 -03:00
|
|
|
#include <AP_Arming/AP_Arming.h>
|
2019-11-03 20:18:01 -04:00
|
|
|
#include <AP_Avoidance/AP_Avoidance.h>
|
2019-06-13 23:43:01 -03:00
|
|
|
#include <AP_GPS/AP_GPS.h>
|
2019-08-31 12:23:08 -03:00
|
|
|
#include <AC_Fence/AC_Fence.h>
|
2020-10-08 22:32:03 -03:00
|
|
|
#include <AP_OpticalFlow/AP_OpticalFlow.h>
|
2020-03-28 21:24:48 -03:00
|
|
|
#include <AP_VisualOdom/AP_VisualOdom.h>
|
2020-03-02 01:56:48 -04:00
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
2020-11-22 09:24:47 -04:00
|
|
|
#include <AP_Mount/AP_Mount.h>
|
2021-02-17 15:15:38 -04:00
|
|
|
#include <AP_VideoTX/AP_VideoTX.h>
|
2021-09-21 08:33:36 -03:00
|
|
|
#include <AP_Torqeedo/AP_Torqeedo.h>
|
2022-01-05 06:26:39 -04:00
|
|
|
#include <AP_Vehicle/AP_Vehicle_Type.h>
|
2018-06-08 00:37:51 -03:00
|
|
|
|
2019-06-18 12:37:19 -03:00
|
|
|
#define SWITCH_DEBOUNCE_TIME_MS 200
|
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo RC_Channel::var_info[] = {
|
2012-08-17 03:22:48 -03:00
|
|
|
// @Param: MIN
|
|
|
|
// @DisplayName: RC min PWM
|
2017-05-15 20:23:19 -03:00
|
|
|
// @Description: RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
|
2017-05-02 10:49:03 -03:00
|
|
|
// @Units: PWM
|
2012-08-17 03:22:48 -03:00
|
|
|
// @Range: 800 2200
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_GROUPINFO("MIN", 1, RC_Channel, radio_min, 1100),
|
2012-08-17 03:22:48 -03:00
|
|
|
|
|
|
|
// @Param: TRIM
|
|
|
|
// @DisplayName: RC trim PWM
|
2017-05-15 20:23:19 -03:00
|
|
|
// @Description: RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
|
2017-05-02 10:49:03 -03:00
|
|
|
// @Units: PWM
|
2012-08-17 03:22:48 -03:00
|
|
|
// @Range: 800 2200
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_GROUPINFO("TRIM", 2, RC_Channel, radio_trim, 1500),
|
2012-08-17 03:22:48 -03:00
|
|
|
|
|
|
|
// @Param: MAX
|
|
|
|
// @DisplayName: RC max PWM
|
2017-05-15 20:23:19 -03:00
|
|
|
// @Description: RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
|
2017-05-02 10:49:03 -03:00
|
|
|
// @Units: PWM
|
2012-08-17 03:22:48 -03:00
|
|
|
// @Range: 800 2200
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Advanced
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_GROUPINFO("MAX", 3, RC_Channel, radio_max, 1900),
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// @Param: REVERSED
|
|
|
|
// @DisplayName: RC reversed
|
2017-02-07 01:32:57 -04:00
|
|
|
// @Description: Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
|
2016-10-22 07:27:40 -03:00
|
|
|
// @Values: 0:Normal,1:Reversed
|
2012-08-17 03:22:48 -03:00
|
|
|
// @User: Advanced
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_GROUPINFO("REVERSED", 4, RC_Channel, reversed, 0),
|
2013-07-13 00:18:54 -03:00
|
|
|
|
2012-08-17 03:22:48 -03:00
|
|
|
// @Param: DZ
|
|
|
|
// @DisplayName: RC dead-zone
|
2017-05-15 20:23:19 -03:00
|
|
|
// @Description: PWM dead zone in microseconds around trim or bottom
|
2017-05-02 10:49:03 -03:00
|
|
|
// @Units: PWM
|
2013-11-26 09:34:28 -04:00
|
|
|
// @Range: 0 200
|
2012-08-17 03:22:48 -03:00
|
|
|
// @User: Advanced
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_GROUPINFO("DZ", 5, RC_Channel, dead_zone, 0),
|
2013-07-13 00:18:54 -03:00
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
// @Param: OPTION
|
|
|
|
// @DisplayName: RC input option
|
|
|
|
// @Description: Function assigned to this RC channel
|
2022-08-30 04:29:24 -03:00
|
|
|
// @Values{Copter}: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:RangeFinder, 11:Fence, 13:Super Simple Mode, 14:Acro Trainer, 15:Sprayer, 16:Auto, 17:AutoTune, 18:Land, 19:Gripper, 21:Parachute Enable, 22:Parachute Release, 23:Parachute 3pos, 24:Auto Mission Reset, 25:AttCon Feed Forward, 26:AttCon Accel Limits, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Copter Sound, 31:Motor Emergency Stop, 32:Motor Interlock, 33:Brake, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 37:Throw, 38:ADSB Avoidance En, 39:PrecLoiter, 40:Proximity Avoidance, 41:ArmDisarm (4.1 and lower), 42:SmartRTL, 43:InvertedFlight, 46:RC Override Enable, 47:User Function 1, 48:User Function 2, 49:User Function 3, 52:Acro, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 60:ZigZag, 61:ZigZag SaveWP, 62:Compass Learn, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 68:Stabilize, 69:PosHold, 70:AltHold, 71:FlowHold, 72:Circle, 73:Drift, 75:SurfaceTrackingUpDown, 76:Standby Mode, 78:RunCam Control, 79:RunCam OSD Control, 80:VisOdom Align, 81:Disarm, 83:ZigZag Auto, 84:Air Mode, 85:Generator, 90:EKF Pos Source, 94:VTX Power, 99:AUTO RTL, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 151:Turtle, 152:simple heading reset, 153:ArmDisarm (4.2 and higher), 154:ArmDisarm with AirMode (4.2 and higher), 158:Optflow Calibration, 159:Force Flying, 161:Turbine Start(heli), 162:FFT Tune, 163:Mount Lock, 164:Pause Stream Logging, 165:Arm/Emergency Motor Stop, 212:Mount Roll, 213:Mount Pitch, 214:Mount Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8
|
|
|
|
// @Values{Rover}: 0:Do Nothing, 4:RTL, 5:Save Trim (4.1 and lower), 7:Save WP, 9:Camera Trigger, 11:Fence, 16:Auto, 19:Gripper, 24:Auto Mission Reset, 27:Retract Mount, 28:Relay On/Off, 30:Lost Rover Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 40:Proximity Avoidance, 41:ArmDisarm (4.1 and lower), 42:SmartRTL, 46:RC Override Enable, 50:LearnCruise, 51:Manual, 52:Acro, 53:Steering, 54:Hold, 55:Guided, 56:Loiter, 57:Follow, 58:Clear Waypoints, 59:Simple Mode, 62:Compass Learn, 63:Sailboat Tack, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 74:Sailboat motoring 3pos, 78:RunCam Control, 79:RunCam OSD Control, 80:Viso Align, 81:Disarm, 90:EKF Pos Source, 94:VTX Power, 97:Windvane home heading direction offset, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 106:Disable Airspeed Use, 153:ArmDisarm (4.2 and higher), 155: set steering trim to current servo and RC, 156:Torqeedo Clear Err, 162:FFT Tune, 163:Mount Lock, 164:Pause Stream Logging, 165:Arm/Emergency Motor Stop, 201:Roll, 202:Pitch, 207:MainSail, 208:Flap, 211:Walking Height, 212:Mount Roll, 213:Mount Pitch, 214:Mount Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8
|
|
|
|
// @Values{Plane}: 0:Do Nothing, 4:ModeRTL, 9:Camera Trigger, 11:Fence, 16:ModeAuto, 22:Parachute Release, 24:Auto Mission Reset, 27:Retract Mount, 28:Relay On/Off, 29:Landing Gear, 30:Lost Plane Sound, 31:Motor Emergency Stop, 34:Relay2 On/Off, 35:Relay3 On/Off, 36:Relay4 On/Off, 38:ADSB Avoidance En, 41:ArmDisarm (4.1 and lower), 43:InvertedFlight, 46:RC Override Enable, 51:ModeManual, 52: ModeACRO, 55:ModeGuided, 56:ModeLoiter, 58:Clear Waypoints, 62:Compass Learn, 64:Reverse Throttle, 65:GPS Disable, 66:Relay5 On/Off, 67:Relay6 On/Off, 72:ModeCircle, 77:ModeTakeoff, 78:RunCam Control, 79:RunCam OSD Control, 81:Disarm, 82:QAssist 3pos, 84:Air Mode, 85:Generator, 86: Non Auto Terrain Follow Disable, 87:Crow Select, 88:Soaring Enable, 89:Landing Flare, 90:EKF Pos Source, 91:Airspeed Ratio Calibration, 92:FBWA, 94:VTX Power, 95:FBWA taildragger takeoff mode, 96:trigger re-reading of mode switch, 98: ModeTraining, 100:KillIMU1, 101:KillIMU2, 102:Camera Mode Toggle, 105:GPS Disable Yaw, 106:Disable Airspeed Use, 107: EnableFixedWingAutotune, 108: ModeQRTL, 150: CRUISE, 153:ArmDisarm (4.2 and higher), 154:ArmDisarm with Quadplane AirMode (4.2 and higher), 155: set roll pitch and yaw trim to current servo and RC, 157: Force FS Action to FBWA, 158:Optflow Calibration, 160:Weathervane Enable, 162:FFT Tune, 163:Mount Lock, 164:Pause Stream Logging, 165:Arm/Emergency Motor Stop, 208:Flap, 209: Forward Throttle, 210: Airbrakes, 212:Mount Roll, 213:Mount Pitch, 214:Mount Yaw, 215:Mount2 Roll, 216:Mount2 Pitch, 217:Mount2 Yaw, 300:Scripting1, 301:Scripting2, 302:Scripting3, 303:Scripting4, 304:Scripting5, 305:Scripting6, 306:Scripting7, 307:Scripting8
|
2022-07-26 20:41:04 -03:00
|
|
|
// @Values{Blimp}: 0:Do Nothing, 18:Land, 46:RC Override Enable, 65:GPS Disable, 81:Disarm, 90:EKF Pos Source, 100:KillIMU1, 101:KillIMU2, 153:ArmDisarm, 164:Pause Stream Logging
|
2018-04-13 23:22:14 -03:00
|
|
|
// @User: Standard
|
2021-06-17 04:27:23 -03:00
|
|
|
AP_GROUPINFO_FRAME("OPTION", 6, RC_Channel, option, 0, AP_PARAM_FRAME_COPTER|AP_PARAM_FRAME_ROVER|AP_PARAM_FRAME_PLANE|AP_PARAM_FRAME_BLIMP),
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2012-08-17 03:22:48 -03:00
|
|
|
AP_GROUPEND
|
2012-02-11 07:54:21 -04:00
|
|
|
};
|
|
|
|
|
2012-05-31 18:59:03 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
// constructor
|
|
|
|
RC_Channel::RC_Channel(void)
|
2010-12-20 23:53:26 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
2010-12-20 23:53:26 -04:00
|
|
|
}
|
|
|
|
|
2020-02-21 23:22:30 -04:00
|
|
|
void RC_Channel::set_range(uint16_t high)
|
2011-05-05 14:46:11 -03:00
|
|
|
{
|
2022-02-25 02:01:06 -04:00
|
|
|
type_in = ControlType::RANGE;
|
2016-10-22 07:27:40 -03:00
|
|
|
high_in = high;
|
2015-12-06 17:25:32 -04:00
|
|
|
}
|
|
|
|
|
2020-02-21 23:22:30 -04:00
|
|
|
void RC_Channel::set_angle(uint16_t angle)
|
2015-12-06 17:25:32 -04:00
|
|
|
{
|
2022-02-25 02:01:06 -04:00
|
|
|
type_in = ControlType::ANGLE;
|
2016-10-22 07:27:40 -03:00
|
|
|
high_in = angle;
|
2015-12-06 17:25:32 -04:00
|
|
|
}
|
|
|
|
|
2020-02-21 23:22:30 -04:00
|
|
|
void RC_Channel::set_default_dead_zone(int16_t dzone)
|
2015-12-06 17:25:32 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
dead_zone.set_default(abs(dzone));
|
2011-05-05 14:46:11 -03:00
|
|
|
}
|
2010-11-28 03:03:23 -04:00
|
|
|
|
2020-02-21 23:22:30 -04:00
|
|
|
bool RC_Channel::get_reverse(void) const
|
2010-11-23 15:28:19 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
return bool(reversed.get());
|
2010-11-23 15:28:19 -04:00
|
|
|
}
|
|
|
|
|
2018-07-24 22:50:01 -03:00
|
|
|
// read input from hal.rcin or overrides
|
2020-02-21 23:22:30 -04:00
|
|
|
bool RC_Channel::update(void)
|
2010-11-23 17:20:29 -04:00
|
|
|
{
|
2019-03-29 07:27:27 -03:00
|
|
|
if (has_override() && !rc().ignore_overrides()) {
|
2018-04-25 23:06:19 -03:00
|
|
|
radio_in = override_value;
|
2020-05-18 19:37:55 -03:00
|
|
|
} else if (rc().has_had_rc_receiver() && !rc().ignore_receiver()) {
|
2018-07-24 22:50:01 -03:00
|
|
|
radio_in = hal.rcin->read(ch_in);
|
2018-04-25 23:06:19 -03:00
|
|
|
} else {
|
2018-07-24 22:50:01 -03:00
|
|
|
return false;
|
2018-04-25 23:06:19 -03:00
|
|
|
}
|
2012-08-17 03:22:48 -03:00
|
|
|
|
2022-02-25 02:01:06 -04:00
|
|
|
if (type_in == ControlType::RANGE) {
|
2016-10-22 07:27:40 -03:00
|
|
|
control_in = pwm_to_range();
|
2012-11-05 05:49:42 -04:00
|
|
|
} else {
|
2022-02-25 02:01:06 -04:00
|
|
|
// ControlType::ANGLE
|
2016-10-22 07:27:40 -03:00
|
|
|
control_in = pwm_to_angle();
|
2012-08-17 03:22:48 -03:00
|
|
|
}
|
2018-07-24 22:50:01 -03:00
|
|
|
|
|
|
|
return true;
|
2010-11-23 15:28:19 -04:00
|
|
|
}
|
|
|
|
|
2014-11-17 18:00:31 -04:00
|
|
|
/*
|
|
|
|
return the center stick position expressed as a control_in value
|
|
|
|
used for thr_mid in copter
|
|
|
|
*/
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t RC_Channel::get_control_mid() const
|
|
|
|
{
|
2022-02-25 02:01:06 -04:00
|
|
|
if (type_in == ControlType::RANGE) {
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t r_in = (radio_min.get() + radio_max.get())/2;
|
2014-11-17 18:00:31 -04:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t radio_trim_low = radio_min + dead_zone;
|
2014-11-17 18:00:31 -04:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
return (((int32_t)(high_in) * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_max - radio_trim_low));
|
2014-11-17 18:00:31 -04:00
|
|
|
} else {
|
|
|
|
return 0;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2012-11-05 08:37:25 -04:00
|
|
|
/*
|
|
|
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
|
|
|
the current radio_in value using the specified dead_zone
|
|
|
|
*/
|
2020-02-21 23:22:30 -04:00
|
|
|
int16_t RC_Channel::pwm_to_angle_dz_trim(uint16_t _dead_zone, uint16_t _trim) const
|
2010-11-23 15:28:19 -04:00
|
|
|
{
|
2017-01-06 21:02:32 -04:00
|
|
|
int16_t radio_trim_high = _trim + _dead_zone;
|
|
|
|
int16_t radio_trim_low = _trim - _dead_zone;
|
2012-02-19 01:08:17 -04:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t reverse_mul = (reversed?-1:1);
|
2020-07-31 05:37:30 -03:00
|
|
|
|
|
|
|
// don't allow out of range values
|
|
|
|
int16_t r_in = constrain_int16(radio_in, radio_min.get(), radio_max.get());
|
|
|
|
|
|
|
|
if (r_in > radio_trim_high && radio_max != radio_trim_high) {
|
|
|
|
return reverse_mul * ((int32_t)high_in * (int32_t)(r_in - radio_trim_high)) / (int32_t)(radio_max - radio_trim_high);
|
|
|
|
} else if (r_in < radio_trim_low && radio_trim_low != radio_min) {
|
|
|
|
return reverse_mul * ((int32_t)high_in * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_trim_low - radio_min);
|
2016-10-22 07:27:40 -03:00
|
|
|
} else {
|
2012-08-17 03:22:48 -03:00
|
|
|
return 0;
|
2016-10-22 07:27:40 -03:00
|
|
|
}
|
2010-12-20 23:53:26 -04:00
|
|
|
}
|
|
|
|
|
2015-12-26 06:58:26 -04:00
|
|
|
/*
|
|
|
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
|
|
|
the current radio_in value using the specified dead_zone
|
|
|
|
*/
|
2020-02-21 23:22:30 -04:00
|
|
|
int16_t RC_Channel::pwm_to_angle_dz(uint16_t _dead_zone) const
|
2015-12-26 06:58:26 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
return pwm_to_angle_dz_trim(_dead_zone, radio_trim);
|
2015-12-26 06:58:26 -04:00
|
|
|
}
|
|
|
|
|
2012-11-05 08:37:25 -04:00
|
|
|
/*
|
|
|
|
return an "angle in centidegrees" (normally -4500 to 4500) from
|
|
|
|
the current radio_in value
|
|
|
|
*/
|
2020-02-21 23:22:30 -04:00
|
|
|
int16_t RC_Channel::pwm_to_angle() const
|
2012-11-05 08:37:25 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
return pwm_to_angle_dz(dead_zone);
|
2012-11-05 08:37:25 -04:00
|
|
|
}
|
|
|
|
|
2010-11-23 15:28:19 -04:00
|
|
|
|
2012-12-04 02:27:18 -04:00
|
|
|
/*
|
|
|
|
convert a pulse width modulation value to a value in the configured
|
|
|
|
range, using the specified deadzone
|
|
|
|
*/
|
2020-02-21 23:22:30 -04:00
|
|
|
int16_t RC_Channel::pwm_to_range_dz(uint16_t _dead_zone) const
|
2010-11-23 15:28:19 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t r_in = constrain_int16(radio_in, radio_min.get(), radio_max.get());
|
2012-05-31 18:59:03 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
if (reversed) {
|
|
|
|
r_in = radio_max.get() - (r_in - radio_min.get());
|
2012-09-16 02:05:26 -03:00
|
|
|
}
|
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t radio_trim_low = radio_min + _dead_zone;
|
2011-09-27 02:12:39 -03:00
|
|
|
|
2016-10-22 07:27:40 -03:00
|
|
|
if (r_in > radio_trim_low) {
|
|
|
|
return (((int32_t)(high_in) * (int32_t)(r_in - radio_trim_low)) / (int32_t)(radio_max - radio_trim_low));
|
|
|
|
}
|
|
|
|
return 0;
|
2010-11-23 15:28:19 -04:00
|
|
|
}
|
|
|
|
|
2012-12-04 02:27:18 -04:00
|
|
|
/*
|
|
|
|
convert a pulse width modulation value to a value in the configured
|
|
|
|
range
|
|
|
|
*/
|
2020-02-21 23:22:30 -04:00
|
|
|
int16_t RC_Channel::pwm_to_range() const
|
2012-12-04 02:27:18 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
return pwm_to_range_dz(dead_zone);
|
2012-12-04 02:27:18 -04:00
|
|
|
}
|
|
|
|
|
2011-09-27 02:12:39 -03:00
|
|
|
|
2018-10-12 19:56:44 -03:00
|
|
|
int16_t RC_Channel::get_control_in_zero_dz(void) const
|
2010-11-23 15:28:19 -04:00
|
|
|
{
|
2022-02-25 02:01:06 -04:00
|
|
|
if (type_in == ControlType::RANGE) {
|
2016-10-22 07:27:40 -03:00
|
|
|
return pwm_to_range_dz(0);
|
2014-03-26 03:38:27 -03:00
|
|
|
}
|
2016-10-22 07:27:40 -03:00
|
|
|
return pwm_to_angle_dz(0);
|
2010-11-23 15:28:19 -04:00
|
|
|
}
|
|
|
|
|
2010-12-27 19:03:26 -04:00
|
|
|
// ------------------------------------------
|
2010-12-25 21:17:04 -04:00
|
|
|
|
2020-02-21 23:22:30 -04:00
|
|
|
float RC_Channel::norm_input() const
|
2010-12-27 19:03:26 -04:00
|
|
|
{
|
2014-03-15 06:43:13 -03:00
|
|
|
float ret;
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t reverse_mul = (reversed?-1:1);
|
|
|
|
if (radio_in < radio_trim) {
|
|
|
|
if (radio_min >= radio_trim) {
|
2015-11-30 06:53:54 -04:00
|
|
|
return 0.0f;
|
|
|
|
}
|
2016-10-22 07:27:40 -03:00
|
|
|
ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_trim - radio_min);
|
2015-02-17 21:47:56 -04:00
|
|
|
} else {
|
2016-10-22 07:27:40 -03:00
|
|
|
if (radio_max <= radio_trim) {
|
2015-11-30 06:53:54 -04:00
|
|
|
return 0.0f;
|
|
|
|
}
|
2016-10-22 07:27:40 -03:00
|
|
|
ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_max - radio_trim);
|
2015-02-17 21:47:56 -04:00
|
|
|
}
|
2014-03-15 06:43:13 -03:00
|
|
|
return constrain_float(ret, -1.0f, 1.0f);
|
2010-12-27 19:03:26 -04:00
|
|
|
}
|
2010-12-25 21:17:04 -04:00
|
|
|
|
2020-02-21 23:22:30 -04:00
|
|
|
float RC_Channel::norm_input_dz() const
|
2014-11-17 21:44:05 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t dz_min = radio_trim - dead_zone;
|
|
|
|
int16_t dz_max = radio_trim + dead_zone;
|
2014-11-17 21:44:05 -04:00
|
|
|
float ret;
|
2016-10-22 07:27:40 -03:00
|
|
|
int16_t reverse_mul = (reversed?-1:1);
|
|
|
|
if (radio_in < dz_min && dz_min > radio_min) {
|
|
|
|
ret = reverse_mul * (float)(radio_in - dz_min) / (float)(dz_min - radio_min);
|
|
|
|
} else if (radio_in > dz_max && radio_max > dz_max) {
|
|
|
|
ret = reverse_mul * (float)(radio_in - dz_max) / (float)(radio_max - dz_max);
|
2014-11-17 21:44:05 -04:00
|
|
|
} else {
|
|
|
|
ret = 0;
|
|
|
|
}
|
|
|
|
return constrain_float(ret, -1.0f, 1.0f);
|
|
|
|
}
|
|
|
|
|
2020-02-21 23:22:13 -04:00
|
|
|
// return a normalised input for a channel, in range -1 to 1,
|
|
|
|
// ignores trim and deadzone
|
|
|
|
float RC_Channel::norm_input_ignore_trim() const
|
|
|
|
{
|
|
|
|
// sanity check min and max to avoid divide by zero
|
|
|
|
if (radio_max <= radio_min) {
|
|
|
|
return 0.0f;
|
|
|
|
}
|
|
|
|
const float ret = (reversed ? -2.0f : 2.0f) * (((float)(radio_in - radio_min) / (float)(radio_max - radio_min)) - 0.5f);
|
|
|
|
return constrain_float(ret, -1.0f, 1.0f);
|
|
|
|
}
|
|
|
|
|
2014-03-04 18:16:12 -04:00
|
|
|
/*
|
|
|
|
get percentage input from 0 to 100. This ignores the trim value.
|
|
|
|
*/
|
2020-02-21 23:22:30 -04:00
|
|
|
uint8_t RC_Channel::percent_input() const
|
2014-03-04 18:16:12 -04:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
if (radio_in <= radio_min) {
|
|
|
|
return reversed?100:0;
|
2014-03-04 18:16:12 -04:00
|
|
|
}
|
2016-10-22 07:27:40 -03:00
|
|
|
if (radio_in >= radio_max) {
|
|
|
|
return reversed?0:100;
|
2014-03-04 18:16:12 -04:00
|
|
|
}
|
2016-10-22 07:27:40 -03:00
|
|
|
uint8_t ret = 100.0f * (radio_in - radio_min) / (float)(radio_max - radio_min);
|
|
|
|
if (reversed) {
|
2014-03-04 18:16:12 -04:00
|
|
|
ret = 100 - ret;
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2015-10-30 02:46:03 -03:00
|
|
|
/*
|
2019-02-11 02:05:14 -04:00
|
|
|
return true if input is within deadzone of trim
|
2015-10-30 02:46:03 -03:00
|
|
|
*/
|
2018-10-12 19:56:44 -03:00
|
|
|
bool RC_Channel::in_trim_dz() const
|
2015-10-30 02:46:03 -03:00
|
|
|
{
|
2016-10-22 07:27:40 -03:00
|
|
|
return is_bounded_int32(radio_in, radio_trim - dead_zone, radio_trim + dead_zone);
|
2015-10-30 02:46:03 -03:00
|
|
|
}
|
2016-10-11 08:00:48 -03:00
|
|
|
|
2021-11-20 20:03:18 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
return trues if input is within deadzone of min
|
|
|
|
*/
|
2022-03-05 01:10:22 -04:00
|
|
|
bool RC_Channel::in_min_dz() const
|
2021-11-20 20:03:18 -04:00
|
|
|
{
|
|
|
|
return radio_in < radio_min + dead_zone;
|
|
|
|
}
|
|
|
|
|
2020-02-07 21:27:16 -04:00
|
|
|
void RC_Channel::set_override(const uint16_t v, const uint32_t timestamp_ms)
|
2018-04-25 23:06:19 -03:00
|
|
|
{
|
2018-08-02 23:23:53 -03:00
|
|
|
if (!rc().gcs_overrides_enabled()) {
|
|
|
|
return;
|
|
|
|
}
|
2019-05-09 17:52:47 -03:00
|
|
|
|
2020-02-07 21:27:16 -04:00
|
|
|
last_override_time = timestamp_ms != 0 ? timestamp_ms : AP_HAL::millis();
|
2018-04-25 23:06:19 -03:00
|
|
|
override_value = v;
|
2019-03-29 07:59:29 -03:00
|
|
|
rc().new_override_received();
|
2018-04-25 23:06:19 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void RC_Channel::clear_override()
|
|
|
|
{
|
|
|
|
last_override_time = 0;
|
|
|
|
override_value = 0;
|
|
|
|
}
|
|
|
|
|
|
|
|
bool RC_Channel::has_override() const
|
|
|
|
{
|
2020-01-23 01:07:48 -04:00
|
|
|
if (override_value == 0) {
|
2018-08-27 17:03:09 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2020-01-23 01:07:48 -04:00
|
|
|
uint32_t override_timeout_ms;
|
|
|
|
if (!rc().get_override_timeout_ms(override_timeout_ms)) {
|
|
|
|
// timeouts are disabled
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (override_timeout_ms == 0) {
|
|
|
|
// overrides are explicitly disabled by a zero value
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
return (AP_HAL::millis() - last_override_time < override_timeout_ms);
|
2018-04-25 23:06:19 -03:00
|
|
|
}
|
2018-01-08 23:41:02 -04:00
|
|
|
|
2019-05-01 17:43:27 -03:00
|
|
|
/*
|
|
|
|
perform stick mixing on one channel
|
|
|
|
This type of stick mixing reduces the influence of the auto
|
|
|
|
controller as it increases the influence of the users stick input,
|
|
|
|
allowing the user full deflection if needed
|
|
|
|
*/
|
2021-09-18 14:55:21 -03:00
|
|
|
float RC_Channel::stick_mixing(const float servo_in)
|
2019-05-01 17:43:27 -03:00
|
|
|
{
|
|
|
|
float ch_inf = (float)(radio_in - radio_trim);
|
|
|
|
ch_inf = fabsf(ch_inf);
|
|
|
|
ch_inf = MIN(ch_inf, 400.0f);
|
|
|
|
ch_inf = ((400.0f - ch_inf) / 400.0f);
|
|
|
|
|
2021-09-18 14:55:21 -03:00
|
|
|
float servo_out = servo_in;
|
2019-05-01 17:43:27 -03:00
|
|
|
servo_out *= ch_inf;
|
|
|
|
servo_out += control_in;
|
|
|
|
|
|
|
|
return servo_out;
|
|
|
|
}
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
//
|
2022-01-21 05:12:00 -04:00
|
|
|
// support for auxiliary switches:
|
2018-04-13 23:22:14 -03:00
|
|
|
//
|
|
|
|
|
|
|
|
void RC_Channel::reset_mode_switch()
|
|
|
|
{
|
2019-06-18 12:37:19 -03:00
|
|
|
switch_state.current_position = -1;
|
|
|
|
switch_state.debounce_position = -1;
|
2018-04-13 23:22:14 -03:00
|
|
|
read_mode_switch();
|
|
|
|
}
|
|
|
|
|
2021-02-07 09:20:55 -04:00
|
|
|
// read a 6 position switch
|
|
|
|
bool RC_Channel::read_6pos_switch(int8_t& position)
|
2018-04-13 23:22:14 -03:00
|
|
|
{
|
2021-02-07 09:20:55 -04:00
|
|
|
// calculate position of 6 pos switch
|
2018-04-13 23:22:14 -03:00
|
|
|
const uint16_t pulsewidth = get_radio_in();
|
2021-05-11 09:32:53 -03:00
|
|
|
if (pulsewidth <= RC_MIN_LIMIT_PWM || pulsewidth >= RC_MAX_LIMIT_PWM) {
|
2021-02-07 09:20:55 -04:00
|
|
|
return false; // This is an error condition
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
if (pulsewidth < 1231) position = 0;
|
|
|
|
else if (pulsewidth < 1361) position = 1;
|
|
|
|
else if (pulsewidth < 1491) position = 2;
|
|
|
|
else if (pulsewidth < 1621) position = 3;
|
|
|
|
else if (pulsewidth < 1750) position = 4;
|
|
|
|
else position = 5;
|
|
|
|
|
2021-02-07 09:20:55 -04:00
|
|
|
if (!debounce_completed(position)) {
|
|
|
|
return false;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
|
|
|
|
2021-02-07 09:20:55 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
void RC_Channel::read_mode_switch()
|
|
|
|
{
|
|
|
|
int8_t position;
|
|
|
|
if (read_6pos_switch(position)) {
|
|
|
|
// set flight mode and simple mode setting
|
|
|
|
mode_switch_changed(modeswitch_pos_t(position));
|
|
|
|
}
|
2019-06-18 12:37:19 -03:00
|
|
|
}
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2019-06-18 12:37:19 -03:00
|
|
|
bool RC_Channel::debounce_completed(int8_t position)
|
|
|
|
{
|
|
|
|
// switch change not detected
|
|
|
|
if (switch_state.current_position == position) {
|
|
|
|
// reset debouncing
|
|
|
|
switch_state.debounce_position = position;
|
|
|
|
} else {
|
|
|
|
// switch change detected
|
|
|
|
const uint32_t tnow_ms = AP_HAL::millis();
|
|
|
|
|
|
|
|
// position not established yet
|
|
|
|
if (switch_state.debounce_position != position) {
|
|
|
|
switch_state.debounce_position = position;
|
|
|
|
switch_state.last_edge_time_ms = tnow_ms;
|
|
|
|
} else if (tnow_ms - switch_state.last_edge_time_ms >= SWITCH_DEBOUNCE_TIME_MS) {
|
|
|
|
// position estabilished; debounce completed
|
|
|
|
switch_state.current_position = position;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
//
|
2022-01-21 05:12:00 -04:00
|
|
|
// support for auxiliary switches:
|
2018-04-13 23:22:14 -03:00
|
|
|
//
|
|
|
|
|
|
|
|
// init_aux_switch_function - initialize aux functions
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::init_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
|
2018-04-13 23:22:14 -03:00
|
|
|
{
|
|
|
|
// init channel options
|
|
|
|
switch(ch_option) {
|
2019-04-11 15:46:02 -03:00
|
|
|
// the following functions do not need to be initialised:
|
2020-01-07 23:36:43 -04:00
|
|
|
case AUX_FUNC::ARMDISARM:
|
2019-11-09 01:24:46 -04:00
|
|
|
case AUX_FUNC::CAMERA_TRIGGER:
|
|
|
|
case AUX_FUNC::CLEAR_WP:
|
|
|
|
case AUX_FUNC::COMPASS_LEARN:
|
2020-04-30 11:54:22 -03:00
|
|
|
case AUX_FUNC::DISARM:
|
2019-11-09 01:24:46 -04:00
|
|
|
case AUX_FUNC::DO_NOTHING:
|
|
|
|
case AUX_FUNC::LANDING_GEAR:
|
|
|
|
case AUX_FUNC::LOST_VEHICLE_SOUND:
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RELAY:
|
|
|
|
case AUX_FUNC::RELAY2:
|
|
|
|
case AUX_FUNC::RELAY3:
|
|
|
|
case AUX_FUNC::RELAY4:
|
|
|
|
case AUX_FUNC::RELAY5:
|
|
|
|
case AUX_FUNC::RELAY6:
|
2021-08-20 02:40:44 -03:00
|
|
|
case AUX_FUNC::VISODOM_ALIGN:
|
2020-03-02 01:56:48 -04:00
|
|
|
case AUX_FUNC::EKF_LANE_SWITCH:
|
|
|
|
case AUX_FUNC::EKF_YAW_RESET:
|
2019-11-26 23:09:52 -04:00
|
|
|
case AUX_FUNC::GENERATOR: // don't turn generator on or off initially
|
2020-06-17 03:35:46 -03:00
|
|
|
case AUX_FUNC::EKF_POS_SOURCE:
|
2021-09-21 08:33:36 -03:00
|
|
|
case AUX_FUNC::TORQEEDO_CLEAR_ERR:
|
2020-07-07 20:15:05 -03:00
|
|
|
case AUX_FUNC::SCRIPTING_1:
|
|
|
|
case AUX_FUNC::SCRIPTING_2:
|
|
|
|
case AUX_FUNC::SCRIPTING_3:
|
|
|
|
case AUX_FUNC::SCRIPTING_4:
|
|
|
|
case AUX_FUNC::SCRIPTING_5:
|
|
|
|
case AUX_FUNC::SCRIPTING_6:
|
|
|
|
case AUX_FUNC::SCRIPTING_7:
|
|
|
|
case AUX_FUNC::SCRIPTING_8:
|
2021-02-07 09:20:55 -04:00
|
|
|
case AUX_FUNC::VTX_POWER:
|
2020-10-08 22:32:03 -03:00
|
|
|
case AUX_FUNC::OPTFLOW_CAL:
|
2022-02-21 00:00:35 -04:00
|
|
|
case AUX_FUNC::TURBINE_START:
|
2022-08-30 04:29:24 -03:00
|
|
|
case AUX_FUNC::MOUNT1_ROLL:
|
|
|
|
case AUX_FUNC::MOUNT1_PITCH:
|
|
|
|
case AUX_FUNC::MOUNT1_YAW:
|
|
|
|
case AUX_FUNC::MOUNT2_ROLL:
|
|
|
|
case AUX_FUNC::MOUNT2_PITCH:
|
|
|
|
case AUX_FUNC::MOUNT2_YAW:
|
2019-04-03 10:23:06 -03:00
|
|
|
break;
|
2019-11-09 01:24:46 -04:00
|
|
|
case AUX_FUNC::AVOID_ADSB:
|
|
|
|
case AUX_FUNC::AVOID_PROXIMITY:
|
|
|
|
case AUX_FUNC::FENCE:
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::GPS_DISABLE:
|
2020-05-20 23:23:26 -03:00
|
|
|
case AUX_FUNC::GPS_DISABLE_YAW:
|
2019-11-09 01:24:46 -04:00
|
|
|
case AUX_FUNC::GRIPPER:
|
2019-04-18 01:24:02 -03:00
|
|
|
case AUX_FUNC::KILL_IMU1:
|
|
|
|
case AUX_FUNC::KILL_IMU2:
|
2019-11-09 01:24:46 -04:00
|
|
|
case AUX_FUNC::MISSION_RESET:
|
|
|
|
case AUX_FUNC::MOTOR_ESTOP:
|
|
|
|
case AUX_FUNC::RC_OVERRIDE_ENABLE:
|
2019-11-13 19:50:45 -04:00
|
|
|
case AUX_FUNC::RUNCAM_CONTROL:
|
2019-12-21 16:07:24 -04:00
|
|
|
case AUX_FUNC::RUNCAM_OSD_CONTROL:
|
2019-11-09 01:24:46 -04:00
|
|
|
case AUX_FUNC::SPRAYER:
|
2021-06-17 03:03:35 -03:00
|
|
|
case AUX_FUNC::DISABLE_AIRSPEED_USE:
|
2022-03-06 08:51:31 -04:00
|
|
|
case AUX_FUNC::FFT_NOTCH_TUNE:
|
2020-11-22 09:24:47 -04:00
|
|
|
#if HAL_MOUNT_ENABLED
|
|
|
|
case AUX_FUNC::RETRACT_MOUNT:
|
2022-06-01 01:39:42 -03:00
|
|
|
case AUX_FUNC::MOUNT_LOCK:
|
2020-12-10 18:13:18 -04:00
|
|
|
#endif
|
2022-07-26 20:41:04 -03:00
|
|
|
case AUX_FUNC::LOG_PAUSE:
|
2022-08-19 12:06:24 -03:00
|
|
|
case AUX_FUNC::ARM_EMERGENCY_STOP:
|
2022-07-26 20:41:04 -03:00
|
|
|
|
2021-04-29 07:09:43 -03:00
|
|
|
run_aux_function(ch_option, ch_flag, AuxFuncTriggerSource::INIT);
|
2018-06-08 00:37:51 -03:00
|
|
|
break;
|
2018-04-13 23:22:14 -03:00
|
|
|
default:
|
2019-11-06 15:43:24 -04:00
|
|
|
gcs().send_text(MAV_SEVERITY_WARNING, "Failed to init: RC%u_OPTION: %u\n",
|
|
|
|
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
2019-11-10 19:56:40 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2019-11-06 15:43:24 -04:00
|
|
|
AP_BoardConfig::config_error("Failed to init: RC%u_OPTION: %u",
|
|
|
|
(unsigned)(this->ch_in+1), (unsigned)ch_option);
|
2019-11-10 19:56:40 -04:00
|
|
|
#endif
|
2018-04-13 23:22:14 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-06-02 22:42:20 -03:00
|
|
|
#if !HAL_MINIMIZE_FEATURES
|
|
|
|
|
|
|
|
const RC_Channel::LookupTable RC_Channel::lookuptable[] = {
|
|
|
|
{ AUX_FUNC::SAVE_WP,"SaveWaypoint"},
|
|
|
|
{ AUX_FUNC::CAMERA_TRIGGER,"CameraTrigger"},
|
|
|
|
{ AUX_FUNC::RANGEFINDER,"Rangefinder"},
|
|
|
|
{ AUX_FUNC::FENCE,"Fence"},
|
|
|
|
{ AUX_FUNC::SPRAYER,"Sprayer"},
|
|
|
|
{ AUX_FUNC::PARACHUTE_ENABLE,"ParachuteEnable"},
|
|
|
|
{ AUX_FUNC::PARACHUTE_RELEASE,"ParachuteRelease"},
|
|
|
|
{ AUX_FUNC::PARACHUTE_3POS,"Parachute3Position"},
|
|
|
|
{ AUX_FUNC::MISSION_RESET,"MissionReset"},
|
|
|
|
{ AUX_FUNC::RETRACT_MOUNT,"RetractMount"},
|
|
|
|
{ AUX_FUNC::RELAY,"Relay1"},
|
2020-11-12 20:32:05 -04:00
|
|
|
{ AUX_FUNC::MOTOR_ESTOP,"MotorEStop"},
|
2020-06-02 22:42:20 -03:00
|
|
|
{ AUX_FUNC::MOTOR_INTERLOCK,"MotorInterlock"},
|
|
|
|
{ AUX_FUNC::RELAY2,"Relay2"},
|
|
|
|
{ AUX_FUNC::RELAY3,"Relay3"},
|
|
|
|
{ AUX_FUNC::RELAY4,"Relay4"},
|
|
|
|
{ AUX_FUNC::PRECISION_LOITER,"PrecisionLoiter"},
|
2020-08-28 20:04:45 -03:00
|
|
|
{ AUX_FUNC::AVOID_PROXIMITY,"AvoidProximity"},
|
2020-06-02 22:42:20 -03:00
|
|
|
{ AUX_FUNC::WINCH_ENABLE,"WinchEnable"},
|
|
|
|
{ AUX_FUNC::WINCH_CONTROL,"WinchControl"},
|
|
|
|
{ AUX_FUNC::CLEAR_WP,"ClearWaypoint"},
|
|
|
|
{ AUX_FUNC::COMPASS_LEARN,"CompassLearn"},
|
|
|
|
{ AUX_FUNC::SAILBOAT_TACK,"SailboatTack"},
|
|
|
|
{ AUX_FUNC::GPS_DISABLE,"GPSDisable"},
|
2020-05-20 23:23:26 -03:00
|
|
|
{ AUX_FUNC::GPS_DISABLE_YAW,"GPSDisableYaw"},
|
2021-06-17 03:03:35 -03:00
|
|
|
{ AUX_FUNC::DISABLE_AIRSPEED_USE,"DisableAirspeedUse"},
|
2020-06-02 22:42:20 -03:00
|
|
|
{ AUX_FUNC::RELAY5,"Relay5"},
|
|
|
|
{ AUX_FUNC::RELAY6,"Relay6"},
|
|
|
|
{ AUX_FUNC::SAILBOAT_MOTOR_3POS,"SailboatMotor"},
|
|
|
|
{ AUX_FUNC::SURFACE_TRACKING,"SurfaceTracking"},
|
|
|
|
{ AUX_FUNC::RUNCAM_CONTROL,"RunCamControl"},
|
|
|
|
{ AUX_FUNC::RUNCAM_OSD_CONTROL,"RunCamOSDControl"},
|
2021-08-20 02:40:44 -03:00
|
|
|
{ AUX_FUNC::VISODOM_ALIGN,"VisOdomAlign"},
|
2022-05-15 12:52:59 -03:00
|
|
|
{ AUX_FUNC::AIRMODE, "AirMode"},
|
2020-06-17 03:35:46 -03:00
|
|
|
{ AUX_FUNC::EKF_POS_SOURCE,"EKFPosSource"},
|
2020-06-02 22:42:20 -03:00
|
|
|
{ AUX_FUNC::CAM_MODE_TOGGLE,"CamModeToggle"},
|
2020-06-28 23:08:05 -03:00
|
|
|
{ AUX_FUNC::GENERATOR,"Generator"},
|
2020-11-24 10:13:10 -04:00
|
|
|
{ AUX_FUNC::ARSPD_CALIBRATE,"Calibrate Airspeed"},
|
2021-09-21 08:33:36 -03:00
|
|
|
{ AUX_FUNC::TORQEEDO_CLEAR_ERR, "Torqeedo Clear Err"},
|
2021-10-24 02:20:43 -03:00
|
|
|
{ AUX_FUNC::EMERGENCY_LANDING_EN, "Emergency Landing"},
|
2022-01-23 18:07:53 -04:00
|
|
|
{ AUX_FUNC::WEATHER_VANE_ENABLE, "Weathervane"},
|
2022-02-21 00:00:35 -04:00
|
|
|
{ AUX_FUNC::TURBINE_START, "Turbine Start"},
|
2022-03-06 08:51:31 -04:00
|
|
|
{ AUX_FUNC::FFT_NOTCH_TUNE, "FFT Notch Tuning"},
|
2022-06-01 01:39:42 -03:00
|
|
|
{ AUX_FUNC::MOUNT_LOCK, "MountLock"},
|
2022-07-26 20:41:04 -03:00
|
|
|
{ AUX_FUNC::LOG_PAUSE, "Pause Stream Logging"},
|
2020-06-02 22:42:20 -03:00
|
|
|
};
|
|
|
|
|
|
|
|
/* lookup the announcement for switch change */
|
|
|
|
const char *RC_Channel::string_for_aux_function(AUX_FUNC function) const
|
|
|
|
{
|
2022-05-05 20:44:22 -03:00
|
|
|
for (const struct LookupTable &entry : lookuptable) {
|
2020-06-02 22:42:20 -03:00
|
|
|
if (entry.option == function) {
|
|
|
|
return entry.announcement;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
#endif // HAL_MINIMIZE_FEATURES
|
|
|
|
|
2019-05-20 21:41:52 -03:00
|
|
|
/*
|
|
|
|
read an aux channel. Return true if a switch has changed
|
|
|
|
*/
|
|
|
|
bool RC_Channel::read_aux()
|
2018-04-13 23:22:14 -03:00
|
|
|
{
|
|
|
|
const aux_func_t _option = (aux_func_t)option.get();
|
2019-04-03 10:23:06 -03:00
|
|
|
if (_option == AUX_FUNC::DO_NOTHING) {
|
2018-04-13 23:22:14 -03:00
|
|
|
// may wish to add special cases for other "AUXSW" things
|
|
|
|
// here e.g. RCMAP_ROLL etc once they become options
|
2019-05-20 21:41:52 -03:00
|
|
|
return false;
|
2021-02-07 09:20:55 -04:00
|
|
|
} else if (_option == AUX_FUNC::VTX_POWER) {
|
|
|
|
int8_t position;
|
|
|
|
if (read_6pos_switch(position)) {
|
|
|
|
AP::vtx().change_power(position);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
2021-02-07 09:20:55 -04:00
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
AuxSwitchPos new_position;
|
2019-01-07 22:19:34 -04:00
|
|
|
if (!read_3pos_switch(new_position)) {
|
2019-05-20 21:41:52 -03:00
|
|
|
return false;
|
2019-01-07 22:19:34 -04:00
|
|
|
}
|
2019-06-18 12:37:19 -03:00
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
if (!debounce_completed((int8_t)new_position)) {
|
2019-05-20 21:41:52 -03:00
|
|
|
return false;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
|
|
|
|
2020-06-02 22:42:20 -03:00
|
|
|
#if !HAL_MINIMIZE_FEATURES
|
|
|
|
// announce the change to the GCS:
|
|
|
|
const char *aux_string = string_for_aux_function(_option);
|
|
|
|
if (aux_string != nullptr) {
|
|
|
|
const char *temp = nullptr;
|
|
|
|
switch (new_position) {
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
temp = "HIGH";
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
temp = "MIDDLE";
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
temp = "LOW";
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "%s %s", aux_string, temp);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
// debounced; undertake the action:
|
2021-04-29 07:09:43 -03:00
|
|
|
run_aux_function(_option, new_position, AuxFuncTriggerSource::RC);
|
2019-05-20 21:41:52 -03:00
|
|
|
return true;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_armdisarm(const AuxSwitchPos ch_flag)
|
2020-01-07 23:42:02 -04:00
|
|
|
{
|
|
|
|
// arm or disarm the vehicle
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2020-01-07 23:42:02 -04:00
|
|
|
AP::arming().arm(AP_Arming::Method::AUXSWITCH, true);
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2020-01-07 23:42:02 -04:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW:
|
2020-02-21 09:09:57 -04:00
|
|
|
AP::arming().disarm(AP_Arming::Method::AUXSWITCH);
|
2020-01-07 23:42:02 -04:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_avoid_adsb(const AuxSwitchPos ch_flag)
|
2019-11-03 20:18:01 -04:00
|
|
|
{
|
2020-09-19 05:41:21 -03:00
|
|
|
#if HAL_ADSB_ENABLED
|
2019-11-03 20:18:01 -04:00
|
|
|
AP_Avoidance *avoidance = AP::ap_avoidance();
|
|
|
|
if (avoidance == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
AP_ADSB *adsb = AP::ADSB();
|
|
|
|
if (adsb == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2020-06-02 23:21:50 -03:00
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
2019-11-03 20:18:01 -04:00
|
|
|
// try to enable AP_Avoidance
|
2020-10-28 10:46:28 -03:00
|
|
|
if (!adsb->enabled() || !adsb->healthy()) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB not available");
|
2019-11-03 20:18:01 -04:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
avoidance->enable();
|
|
|
|
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_ENABLE);
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Enabled");
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// disable AP_Avoidance
|
|
|
|
avoidance->disable();
|
|
|
|
AP::logger().Write_Event(LogEvent::AVOIDANCE_ADSB_DISABLE);
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "ADSB Avoidance Disabled");
|
2020-09-19 05:41:21 -03:00
|
|
|
#endif
|
2019-11-03 20:18:01 -04:00
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_avoid_proximity(const AuxSwitchPos ch_flag)
|
2018-10-25 04:36:20 -03:00
|
|
|
{
|
2022-01-05 06:26:39 -04:00
|
|
|
#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane)
|
2018-10-25 04:36:20 -03:00
|
|
|
AC_Avoid *avoid = AP::ac_avoid();
|
|
|
|
if (avoid == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2018-10-25 04:36:20 -03:00
|
|
|
avoid->proximity_avoidance_enable(true);
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2018-10-25 04:36:20 -03:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW:
|
2018-10-25 04:36:20 -03:00
|
|
|
avoid->proximity_avoidance_enable(false);
|
|
|
|
break;
|
|
|
|
}
|
2022-01-05 06:26:39 -04:00
|
|
|
#endif // !APM_BUILD_ArduPlane
|
2018-10-25 04:36:20 -03:00
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_camera_trigger(const AuxSwitchPos ch_flag)
|
2018-04-13 23:22:14 -03:00
|
|
|
{
|
|
|
|
AP_Camera *camera = AP::camera();
|
|
|
|
if (camera == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2020-06-02 23:21:50 -03:00
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
2018-04-13 23:22:14 -03:00
|
|
|
camera->take_picture();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_runcam_control(const AuxSwitchPos ch_flag)
|
2019-11-13 19:50:45 -04:00
|
|
|
{
|
|
|
|
#if HAL_RUNCAM_ENABLED
|
|
|
|
AP_RunCam *runcam = AP::runcam();
|
|
|
|
if (runcam == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2019-11-13 19:50:45 -04:00
|
|
|
runcam->start_recording();
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2019-12-21 16:07:24 -04:00
|
|
|
runcam->osd_option();
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW:
|
2019-11-13 19:50:45 -04:00
|
|
|
runcam->stop_recording();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_runcam_osd_control(const AuxSwitchPos ch_flag)
|
2019-12-21 16:07:24 -04:00
|
|
|
{
|
|
|
|
#if HAL_RUNCAM_ENABLED
|
|
|
|
AP_RunCam *runcam = AP::runcam();
|
|
|
|
if (runcam == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2019-12-21 16:07:24 -04:00
|
|
|
runcam->enter_osd();
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
case AuxSwitchPos::LOW:
|
2019-12-21 16:07:24 -04:00
|
|
|
runcam->exit_osd();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2019-08-31 12:23:08 -03:00
|
|
|
// enable or disable the fence
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_fence(const AuxSwitchPos ch_flag)
|
2019-08-31 12:23:08 -03:00
|
|
|
{
|
2022-07-19 08:33:13 -03:00
|
|
|
#if AP_FENCE_ENABLED
|
2019-08-31 12:23:08 -03:00
|
|
|
AC_Fence *fence = AP::fence();
|
|
|
|
if (fence == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
fence->enable(ch_flag == AuxSwitchPos::HIGH);
|
2022-03-04 12:40:03 -04:00
|
|
|
#endif
|
2019-08-31 12:23:08 -03:00
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_clear_wp(const AuxSwitchPos ch_flag)
|
2018-08-16 23:44:15 -03:00
|
|
|
{
|
|
|
|
AP_Mission *mission = AP::mission();
|
|
|
|
if (mission == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
2020-06-02 23:21:50 -03:00
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
2018-08-16 23:44:15 -03:00
|
|
|
mission->clear();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
void RC_Channel::do_aux_function_relay(const uint8_t relay, bool val)
|
|
|
|
{
|
|
|
|
AP_ServoRelayEvents *servorelayevents = AP::servorelayevents();
|
|
|
|
if (servorelayevents == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
servorelayevents->do_set_relay(relay, val);
|
|
|
|
}
|
|
|
|
|
2021-09-24 00:10:47 -03:00
|
|
|
#if HAL_GENERATOR_ENABLED
|
2019-11-26 23:09:52 -04:00
|
|
|
void RC_Channel::do_aux_function_generator(const AuxSwitchPos ch_flag)
|
|
|
|
{
|
2020-10-22 14:14:53 -03:00
|
|
|
AP_Generator *generator = AP::generator();
|
2019-11-26 23:09:52 -04:00
|
|
|
if (generator == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch (ch_flag) {
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
generator->stop();
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
generator->idle();
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
generator->run();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_sprayer(const AuxSwitchPos ch_flag)
|
2018-06-08 00:37:51 -03:00
|
|
|
{
|
2020-01-17 18:59:20 -04:00
|
|
|
#if HAL_SPRAYER_ENABLED
|
2018-06-08 00:37:51 -03:00
|
|
|
AC_Sprayer *sprayer = AP::sprayer();
|
|
|
|
if (sprayer == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
sprayer->run(ch_flag == AuxSwitchPos::HIGH);
|
2018-06-08 00:37:51 -03:00
|
|
|
// if we are disarmed the pilot must want to test the pump
|
2020-06-02 23:21:50 -03:00
|
|
|
sprayer->test_pump((ch_flag == AuxSwitchPos::HIGH) && !hal.util->get_soft_armed());
|
2020-01-17 18:59:20 -04:00
|
|
|
#endif // HAL_SPRAYER_ENABLED
|
2018-06-08 00:37:51 -03:00
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_gripper(const AuxSwitchPos ch_flag)
|
2018-06-08 00:37:51 -03:00
|
|
|
{
|
|
|
|
AP_Gripper *gripper = AP::gripper();
|
|
|
|
if (gripper == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch(ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW:
|
2018-06-08 00:37:51 -03:00
|
|
|
gripper->release();
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2018-06-08 00:37:51 -03:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2018-06-08 00:37:51 -03:00
|
|
|
gripper->grab();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_lost_vehicle_sound(const AuxSwitchPos ch_flag)
|
2018-08-27 05:15:51 -03:00
|
|
|
{
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2018-08-27 05:15:51 -03:00
|
|
|
AP_Notify::flags.vehicle_lost = true;
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2018-08-27 05:15:51 -03:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW:
|
2018-08-27 05:15:51 -03:00
|
|
|
AP_Notify::flags.vehicle_lost = false;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_rc_override_enable(const AuxSwitchPos ch_flag)
|
2018-08-02 07:48:04 -03:00
|
|
|
{
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH: {
|
2018-08-02 07:48:04 -03:00
|
|
|
rc().set_gcs_overrides_enabled(true);
|
|
|
|
break;
|
|
|
|
}
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2018-08-02 07:48:04 -03:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW: {
|
2018-08-02 07:48:04 -03:00
|
|
|
rc().set_gcs_overrides_enabled(false);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2020-06-02 23:21:50 -03:00
|
|
|
void RC_Channel::do_aux_function_mission_reset(const AuxSwitchPos ch_flag)
|
2019-06-05 20:39:14 -03:00
|
|
|
{
|
2020-06-02 23:21:50 -03:00
|
|
|
if (ch_flag != AuxSwitchPos::HIGH) {
|
2019-06-05 20:39:14 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
AP_Mission *mission = AP::mission();
|
|
|
|
if (mission == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
mission->reset();
|
|
|
|
}
|
|
|
|
|
2022-03-06 08:51:31 -04:00
|
|
|
void RC_Channel::do_aux_function_fft_notch_tune(const AuxSwitchPos ch_flag)
|
|
|
|
{
|
|
|
|
#if HAL_GYROFFT_ENABLED
|
|
|
|
AP_GyroFFT *fft = AP::fft();
|
|
|
|
if (fft == nullptr) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
switch (ch_flag) {
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
fft->start_notch_tune();
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
fft->stop_notch_tune();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2021-04-28 06:13:53 -03:00
|
|
|
bool RC_Channel::run_aux_function(aux_func_t ch_option, AuxSwitchPos pos, AuxFuncTriggerSource source)
|
|
|
|
{
|
|
|
|
const bool ret = do_aux_function(ch_option, pos);
|
|
|
|
|
|
|
|
// @LoggerMessage: AUXF
|
2022-01-05 02:50:45 -04:00
|
|
|
// @Description: Auxiliary function invocation information
|
2021-04-28 06:13:53 -03:00
|
|
|
// @Field: TimeUS: Time since system startup
|
|
|
|
// @Field: function: ID of triggered function
|
|
|
|
// @Field: pos: switch position when function triggered
|
2022-01-21 05:12:00 -04:00
|
|
|
// @Field: source: source of auxiliary function invocation
|
2021-04-28 06:13:53 -03:00
|
|
|
// @Field: result: true if function was successful
|
|
|
|
AP::logger().Write(
|
|
|
|
"AUXF",
|
|
|
|
"TimeUS,function,pos,source,result",
|
2022-01-13 16:12:37 -04:00
|
|
|
"s#---",
|
2021-04-28 06:13:53 -03:00
|
|
|
"F----",
|
|
|
|
"QHBBB",
|
|
|
|
AP_HAL::micros64(),
|
|
|
|
uint16_t(ch_option),
|
|
|
|
uint8_t(pos),
|
|
|
|
uint8_t(source),
|
|
|
|
uint8_t(ret)
|
|
|
|
);
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2021-02-24 05:48:15 -04:00
|
|
|
bool RC_Channel::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
|
2018-04-13 23:22:14 -03:00
|
|
|
{
|
|
|
|
switch(ch_option) {
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::CAMERA_TRIGGER:
|
2018-04-13 23:22:14 -03:00
|
|
|
do_aux_function_camera_trigger(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-08-31 12:23:08 -03:00
|
|
|
case AUX_FUNC::FENCE:
|
|
|
|
do_aux_function_fence(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::GRIPPER:
|
2018-06-08 00:37:51 -03:00
|
|
|
do_aux_function_gripper(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RC_OVERRIDE_ENABLE:
|
2018-08-02 07:48:04 -03:00
|
|
|
// Allow or disallow RC_Override
|
|
|
|
do_aux_function_rc_override_enable(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::AVOID_PROXIMITY:
|
2018-10-25 04:36:20 -03:00
|
|
|
do_aux_function_avoid_proximity(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RELAY:
|
2020-06-02 23:21:50 -03:00
|
|
|
do_aux_function_relay(0, ch_flag == AuxSwitchPos::HIGH);
|
2018-04-13 23:22:14 -03:00
|
|
|
break;
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RELAY2:
|
2020-06-02 23:21:50 -03:00
|
|
|
do_aux_function_relay(1, ch_flag == AuxSwitchPos::HIGH);
|
2018-04-13 23:22:14 -03:00
|
|
|
break;
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RELAY3:
|
2020-06-02 23:21:50 -03:00
|
|
|
do_aux_function_relay(2, ch_flag == AuxSwitchPos::HIGH);
|
2018-04-13 23:22:14 -03:00
|
|
|
break;
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RELAY4:
|
2020-06-02 23:21:50 -03:00
|
|
|
do_aux_function_relay(3, ch_flag == AuxSwitchPos::HIGH);
|
2018-04-13 23:22:14 -03:00
|
|
|
break;
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RELAY5:
|
2020-06-02 23:21:50 -03:00
|
|
|
do_aux_function_relay(4, ch_flag == AuxSwitchPos::HIGH);
|
2018-10-03 10:03:49 -03:00
|
|
|
break;
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::RELAY6:
|
2020-06-02 23:21:50 -03:00
|
|
|
do_aux_function_relay(5, ch_flag == AuxSwitchPos::HIGH);
|
2018-10-03 10:03:49 -03:00
|
|
|
break;
|
2019-11-13 19:50:45 -04:00
|
|
|
|
|
|
|
case AUX_FUNC::RUNCAM_CONTROL:
|
|
|
|
do_aux_function_runcam_control(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-12-21 16:07:24 -04:00
|
|
|
case AUX_FUNC::RUNCAM_OSD_CONTROL:
|
|
|
|
do_aux_function_runcam_osd_control(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::CLEAR_WP:
|
2018-08-16 23:44:15 -03:00
|
|
|
do_aux_function_clear_wp(ch_flag);
|
|
|
|
break;
|
2019-06-05 20:39:14 -03:00
|
|
|
case AUX_FUNC::MISSION_RESET:
|
|
|
|
do_aux_function_mission_reset(ch_flag);
|
|
|
|
break;
|
2018-04-13 23:22:14 -03:00
|
|
|
|
2019-11-03 20:18:01 -04:00
|
|
|
case AUX_FUNC::AVOID_ADSB:
|
|
|
|
do_aux_function_avoid_adsb(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2022-03-06 08:51:31 -04:00
|
|
|
case AUX_FUNC::FFT_NOTCH_TUNE:
|
|
|
|
do_aux_function_fft_notch_tune(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2021-09-24 00:10:47 -03:00
|
|
|
#if HAL_GENERATOR_ENABLED
|
2019-11-26 23:09:52 -04:00
|
|
|
case AUX_FUNC::GENERATOR:
|
|
|
|
do_aux_function_generator(ch_flag);
|
|
|
|
break;
|
|
|
|
#endif
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::SPRAYER:
|
2018-06-08 00:37:51 -03:00
|
|
|
do_aux_function_sprayer(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::LOST_VEHICLE_SOUND:
|
2018-08-27 05:15:51 -03:00
|
|
|
do_aux_function_lost_vehicle_sound(ch_flag);
|
|
|
|
break;
|
|
|
|
|
2019-05-03 08:26:28 -03:00
|
|
|
case AUX_FUNC::ARMDISARM:
|
2020-01-07 23:42:02 -04:00
|
|
|
do_aux_function_armdisarm(ch_flag);
|
2019-05-03 08:26:28 -03:00
|
|
|
break;
|
|
|
|
|
2020-04-30 11:54:22 -03:00
|
|
|
case AUX_FUNC::DISARM:
|
2020-06-02 23:21:50 -03:00
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
2020-04-30 11:54:22 -03:00
|
|
|
AP::arming().disarm(AP_Arming::Method::AUXSWITCH);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::COMPASS_LEARN:
|
2020-06-02 23:21:50 -03:00
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
2018-10-19 21:00:04 -03:00
|
|
|
Compass &compass = AP::compass();
|
|
|
|
compass.set_learn_type(Compass::LEARN_INFLIGHT, false);
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::LANDING_GEAR: {
|
2019-02-10 01:01:36 -04:00
|
|
|
AP_LandingGear *lg = AP_LandingGear::get_singleton();
|
2018-11-08 20:02:54 -04:00
|
|
|
if (lg == nullptr) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW:
|
2018-11-08 20:02:54 -04:00
|
|
|
lg->set_position(AP_LandingGear::LandingGear_Deploy);
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2018-11-08 20:02:54 -04:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2018-11-08 20:02:54 -04:00
|
|
|
lg->set_position(AP_LandingGear::LandingGear_Retract);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::GPS_DISABLE:
|
2020-06-02 23:21:50 -03:00
|
|
|
AP::gps().force_disable(ch_flag == AuxSwitchPos::HIGH);
|
2018-09-04 23:37:33 -03:00
|
|
|
break;
|
2019-01-20 21:36:26 -04:00
|
|
|
|
2020-05-20 23:23:26 -03:00
|
|
|
case AUX_FUNC::GPS_DISABLE_YAW:
|
|
|
|
AP::gps().set_force_disable_yaw(ch_flag == AuxSwitchPos::HIGH);
|
|
|
|
break;
|
|
|
|
|
2021-06-17 03:03:35 -03:00
|
|
|
case AUX_FUNC::DISABLE_AIRSPEED_USE: {
|
2021-11-01 05:09:55 -03:00
|
|
|
#if AP_AIRSPEED_ENABLED
|
2021-06-17 03:03:35 -03:00
|
|
|
AP_Airspeed *airspeed = AP::airspeed();
|
|
|
|
if (airspeed == nullptr) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
switch (ch_flag) {
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
airspeed->force_disable_use(true);
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
airspeed->force_disable_use(false);
|
|
|
|
break;
|
|
|
|
}
|
2021-11-01 05:09:55 -03:00
|
|
|
#endif
|
2021-06-17 03:03:35 -03:00
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2019-04-03 10:23:06 -03:00
|
|
|
case AUX_FUNC::MOTOR_ESTOP:
|
2019-01-20 21:36:26 -04:00
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH: {
|
2019-01-20 21:36:26 -04:00
|
|
|
SRV_Channels::set_emergency_stop(true);
|
|
|
|
break;
|
|
|
|
}
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2019-01-20 21:36:26 -04:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW: {
|
2019-01-20 21:36:26 -04:00
|
|
|
SRV_Channels::set_emergency_stop(false);
|
|
|
|
break;
|
|
|
|
}
|
2019-04-18 01:24:02 -03:00
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2021-08-20 02:40:44 -03:00
|
|
|
case AUX_FUNC::VISODOM_ALIGN:
|
2020-03-28 21:24:48 -03:00
|
|
|
#if HAL_VISUALODOM_ENABLED
|
2020-06-02 23:21:50 -03:00
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
2020-03-28 21:24:48 -03:00
|
|
|
AP_VisualOdom *visual_odom = AP::visualodom();
|
|
|
|
if (visual_odom != nullptr) {
|
|
|
|
visual_odom->align_sensor_to_vehicle();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
|
2020-06-17 03:35:46 -03:00
|
|
|
case AUX_FUNC::EKF_POS_SOURCE:
|
|
|
|
switch (ch_flag) {
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
// low switches to primary source
|
|
|
|
AP::ahrs().set_posvelyaw_source_set(0);
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
// middle switches to secondary source
|
|
|
|
AP::ahrs().set_posvelyaw_source_set(1);
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
// high switches to tertiary source
|
|
|
|
AP::ahrs().set_posvelyaw_source_set(2);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
|
2020-10-08 22:32:03 -03:00
|
|
|
case AUX_FUNC::OPTFLOW_CAL: {
|
|
|
|
#if AP_OPTICALFLOW_ENABLED
|
2022-08-14 22:31:14 -03:00
|
|
|
AP_OpticalFlow *optflow = AP::opticalflow();
|
2020-10-08 22:32:03 -03:00
|
|
|
if (optflow == nullptr) {
|
|
|
|
gcs().send_text(MAV_SEVERITY_CRITICAL, "OptFlow Cal: failed sensor not enabled");
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
|
|
|
optflow->start_calibration();
|
|
|
|
} else {
|
|
|
|
optflow->stop_calibration();
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2019-07-07 05:06:02 -03:00
|
|
|
#if !HAL_MINIMIZE_FEATURES
|
2019-04-18 01:24:02 -03:00
|
|
|
case AUX_FUNC::KILL_IMU1:
|
2021-05-27 23:18:44 -03:00
|
|
|
AP::ins().kill_imu(0, ch_flag == AuxSwitchPos::HIGH);
|
2019-04-18 01:24:02 -03:00
|
|
|
break;
|
|
|
|
|
|
|
|
case AUX_FUNC::KILL_IMU2:
|
2021-05-27 23:18:44 -03:00
|
|
|
AP::ins().kill_imu(1, ch_flag == AuxSwitchPos::HIGH);
|
2019-04-18 01:24:02 -03:00
|
|
|
break;
|
2019-07-07 05:06:02 -03:00
|
|
|
#endif // HAL_MINIMIZE_FEATURES
|
2019-01-20 21:36:26 -04:00
|
|
|
|
2020-02-09 15:30:22 -04:00
|
|
|
case AUX_FUNC::CAM_MODE_TOGGLE: {
|
|
|
|
// Momentary switch to for cycling camera modes
|
|
|
|
AP_Camera *camera = AP_Camera::get_singleton();
|
|
|
|
if (camera == nullptr) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
switch (ch_flag) {
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::LOW:
|
2020-02-09 15:30:22 -04:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::MIDDLE:
|
2020-02-09 15:30:22 -04:00
|
|
|
// nothing
|
|
|
|
break;
|
2020-06-02 23:21:50 -03:00
|
|
|
case AuxSwitchPos::HIGH:
|
2020-02-09 15:30:22 -04:00
|
|
|
camera->cam_mode_toggle();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2020-11-22 09:24:47 -04:00
|
|
|
case AUX_FUNC::RETRACT_MOUNT: {
|
|
|
|
#if HAL_MOUNT_ENABLED
|
|
|
|
AP_Mount *mount = AP::mount();
|
|
|
|
if (mount == nullptr) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
switch (ch_flag) {
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
mount->set_mode(MAV_MOUNT_MODE_RETRACT);
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
// nothing
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
mount->set_mode_to_default();
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2022-06-01 01:39:42 -03:00
|
|
|
case AUX_FUNC::MOUNT_LOCK: {
|
|
|
|
#if HAL_MOUNT_ENABLED
|
|
|
|
AP_Mount *mount = AP::mount();
|
|
|
|
if (mount == nullptr) {
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
mount->set_yaw_lock(ch_flag == AuxSwitchPos::HIGH);
|
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2022-07-26 20:41:04 -03:00
|
|
|
case AUX_FUNC::LOG_PAUSE: {
|
|
|
|
AP_Logger *logger = AP_Logger::get_singleton();
|
|
|
|
switch (ch_flag) {
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
logger->log_pause(false);
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
// nothing
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
logger->log_pause(true);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2022-08-19 12:06:24 -03:00
|
|
|
case AUX_FUNC::ARM_EMERGENCY_STOP: {
|
|
|
|
switch (ch_flag) {
|
|
|
|
case AuxSwitchPos::HIGH:
|
|
|
|
// request arm, disable emergency motor stop
|
|
|
|
SRV_Channels::set_emergency_stop(false);
|
|
|
|
AP::arming().arm(AP_Arming::Method::AUXSWITCH, true);
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::MIDDLE:
|
|
|
|
// disable emergency motor stop
|
|
|
|
SRV_Channels::set_emergency_stop(false);
|
|
|
|
break;
|
|
|
|
case AuxSwitchPos::LOW:
|
|
|
|
// enable emergency motor stop
|
|
|
|
SRV_Channels::set_emergency_stop(true);
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2020-03-02 01:56:48 -04:00
|
|
|
case AUX_FUNC::EKF_LANE_SWITCH:
|
|
|
|
// used to test emergency lane switch
|
|
|
|
AP::ahrs().check_lane_switch();
|
|
|
|
break;
|
|
|
|
|
|
|
|
case AUX_FUNC::EKF_YAW_RESET:
|
|
|
|
// used to test emergency yaw reset
|
|
|
|
AP::ahrs().request_yaw_reset();
|
|
|
|
break;
|
|
|
|
|
2021-09-21 08:33:36 -03:00
|
|
|
// clear torqeedo error
|
|
|
|
case AUX_FUNC::TORQEEDO_CLEAR_ERR: {
|
|
|
|
#if HAL_TORQEEDO_ENABLED
|
|
|
|
if (ch_flag == AuxSwitchPos::HIGH) {
|
|
|
|
AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton();
|
|
|
|
if (torqeedo != nullptr) {
|
|
|
|
torqeedo->clear_motor_error();
|
|
|
|
}
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
|
2022-08-30 04:29:24 -03:00
|
|
|
// do nothing for these functions
|
|
|
|
case AUX_FUNC::MOUNT1_ROLL:
|
|
|
|
case AUX_FUNC::MOUNT1_PITCH:
|
|
|
|
case AUX_FUNC::MOUNT1_YAW:
|
|
|
|
case AUX_FUNC::MOUNT2_ROLL:
|
|
|
|
case AUX_FUNC::MOUNT2_PITCH:
|
|
|
|
case AUX_FUNC::MOUNT2_YAW:
|
2020-07-07 20:15:05 -03:00
|
|
|
case AUX_FUNC::SCRIPTING_1:
|
|
|
|
case AUX_FUNC::SCRIPTING_2:
|
|
|
|
case AUX_FUNC::SCRIPTING_3:
|
|
|
|
case AUX_FUNC::SCRIPTING_4:
|
|
|
|
case AUX_FUNC::SCRIPTING_5:
|
|
|
|
case AUX_FUNC::SCRIPTING_6:
|
|
|
|
case AUX_FUNC::SCRIPTING_7:
|
|
|
|
case AUX_FUNC::SCRIPTING_8:
|
|
|
|
break;
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
default:
|
2019-07-26 23:09:46 -03:00
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option);
|
2021-02-24 05:48:15 -04:00
|
|
|
return false;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
2021-02-24 05:48:15 -04:00
|
|
|
|
|
|
|
return true;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
void RC_Channel::init_aux()
|
|
|
|
{
|
2020-06-02 23:21:50 -03:00
|
|
|
AuxSwitchPos position;
|
2019-01-07 22:19:34 -04:00
|
|
|
if (!read_3pos_switch(position)) {
|
2020-06-02 23:21:50 -03:00
|
|
|
position = AuxSwitchPos::LOW;
|
2019-01-07 22:19:34 -04:00
|
|
|
}
|
2018-04-13 23:22:14 -03:00
|
|
|
init_aux_function((aux_func_t)option.get(), position);
|
|
|
|
}
|
|
|
|
|
|
|
|
// read_3pos_switch
|
2020-06-02 23:21:50 -03:00
|
|
|
bool RC_Channel::read_3pos_switch(RC_Channel::AuxSwitchPos &ret) const
|
2018-04-13 23:22:14 -03:00
|
|
|
{
|
|
|
|
const uint16_t in = get_radio_in();
|
2021-05-12 05:02:36 -03:00
|
|
|
if (in <= RC_MIN_LIMIT_PWM || in >= RC_MAX_LIMIT_PWM) {
|
2019-01-07 22:19:34 -04:00
|
|
|
return false;
|
|
|
|
}
|
2020-01-04 15:04:16 -04:00
|
|
|
|
|
|
|
// switch is reversed if 'reversed' option set on channel and switches reverse is allowed by RC_OPTIONS
|
|
|
|
bool switch_reversed = reversed && rc().switch_reverse_allowed();
|
|
|
|
|
2021-02-03 13:21:28 -04:00
|
|
|
if (in < AUX_SWITCH_PWM_TRIGGER_LOW) {
|
2020-06-02 23:21:50 -03:00
|
|
|
ret = switch_reversed ? AuxSwitchPos::HIGH : AuxSwitchPos::LOW;
|
2021-02-03 13:21:28 -04:00
|
|
|
} else if (in > AUX_SWITCH_PWM_TRIGGER_HIGH) {
|
2020-06-02 23:21:50 -03:00
|
|
|
ret = switch_reversed ? AuxSwitchPos::LOW : AuxSwitchPos::HIGH;
|
2019-01-07 22:19:34 -04:00
|
|
|
} else {
|
2020-06-02 23:21:50 -03:00
|
|
|
ret = AuxSwitchPos::MIDDLE;
|
2019-01-07 22:19:34 -04:00
|
|
|
}
|
|
|
|
return true;
|
2018-04-13 23:22:14 -03:00
|
|
|
}
|
|
|
|
|
2020-04-30 11:54:22 -03:00
|
|
|
// return switch position value as LOW, MIDDLE, HIGH
|
|
|
|
// if reading the switch fails then it returns LOW
|
2020-06-02 23:21:50 -03:00
|
|
|
RC_Channel::AuxSwitchPos RC_Channel::get_aux_switch_pos() const
|
2020-04-30 11:54:22 -03:00
|
|
|
{
|
2020-06-02 23:21:50 -03:00
|
|
|
AuxSwitchPos position = AuxSwitchPos::LOW;
|
2020-04-30 11:54:22 -03:00
|
|
|
UNUSED_RESULT(read_3pos_switch(position));
|
|
|
|
|
|
|
|
return position;
|
|
|
|
}
|
|
|
|
|
2020-05-02 11:08:50 -03:00
|
|
|
// return switch position value as LOW, MIDDLE, HIGH
|
|
|
|
// if reading the switch fails then it returns LOW
|
2020-06-02 23:21:50 -03:00
|
|
|
RC_Channel::AuxSwitchPos RC_Channels::get_channel_pos(const uint8_t rcmapchan) const
|
2020-05-02 11:08:50 -03:00
|
|
|
{
|
|
|
|
const RC_Channel* chan = rc().channel(rcmapchan-1);
|
2020-06-02 23:21:50 -03:00
|
|
|
return chan != nullptr ? chan->get_aux_switch_pos() : RC_Channel::AuxSwitchPos::LOW;
|
2020-05-02 11:08:50 -03:00
|
|
|
}
|
|
|
|
|
2018-04-13 23:22:14 -03:00
|
|
|
RC_Channel *RC_Channels::find_channel_for_option(const RC_Channel::aux_func_t option)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
|
|
|
RC_Channel *c = channel(i);
|
|
|
|
if (c == nullptr) {
|
|
|
|
// odd?
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if ((RC_Channel::aux_func_t)c->option.get() == option) {
|
|
|
|
return c;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
// duplicate_options_exist - returns true if any options are duplicated
|
|
|
|
bool RC_Channels::duplicate_options_exist()
|
|
|
|
{
|
|
|
|
uint8_t auxsw_option_counts[256] = {};
|
|
|
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
|
|
|
const RC_Channel *c = channel(i);
|
|
|
|
if (c == nullptr) {
|
|
|
|
// odd?
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
const uint16_t option = c->option.get();
|
2018-08-06 22:59:46 -03:00
|
|
|
if (option >= sizeof(auxsw_option_counts)) {
|
2018-04-13 23:22:14 -03:00
|
|
|
continue;
|
|
|
|
}
|
|
|
|
auxsw_option_counts[option]++;
|
|
|
|
}
|
|
|
|
|
|
|
|
for (uint16_t i=0; i<sizeof(auxsw_option_counts); i++) {
|
|
|
|
if (i == 0) { // MAGIC VALUE! This is AUXSW_DO_NOTHING
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if (auxsw_option_counts[i] > 1) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2021-09-13 21:38:43 -03:00
|
|
|
|
|
|
|
// convert option parameter from old to new
|
|
|
|
void RC_Channels::convert_options(const RC_Channel::aux_func_t old_option, const RC_Channel::aux_func_t new_option)
|
|
|
|
{
|
|
|
|
for (uint8_t i=0; i<NUM_RC_CHANNELS; i++) {
|
|
|
|
RC_Channel *c = channel(i);
|
|
|
|
if (c == nullptr) {
|
|
|
|
// odd?
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
if ((RC_Channel::aux_func_t)c->option.get() == old_option) {
|
|
|
|
c->option.set_and_save((int16_t)new_option);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|