RC_Channel: added lane switch RCn_OPTION=103

RC_Channel: added yaw reset switch RCn_OPTION=104
This commit is contained in:
Andrew Tridgell 2020-03-02 16:56:48 +11:00
parent 36031c01a9
commit 6b6f083bf2
2 changed files with 15 additions and 0 deletions

View File

@ -42,6 +42,7 @@ extern const AP_HAL::HAL& hal;
#include <AP_GPS/AP_GPS.h>
#include <AC_Fence/AC_Fence.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#include <AP_AHRS/AP_AHRS.h>
#define SWITCH_DEBOUNCE_TIME_MS 200
@ -464,6 +465,8 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
case AUX_FUNC::RELAY5:
case AUX_FUNC::RELAY6:
case AUX_FUNC::VISODOM_CALIBRATE:
case AUX_FUNC::EKF_LANE_SWITCH:
case AUX_FUNC::EKF_YAW_RESET:
break;
case AUX_FUNC::AVOID_ADSB:
case AUX_FUNC::AVOID_PROXIMITY:
@ -935,6 +938,16 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_po
break;
}
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;
default:
gcs().send_text(MAV_SEVERITY_INFO, "Invalid channel option (%u)", (unsigned int)ch_option);
break;

View File

@ -181,6 +181,8 @@ public:
KILL_IMU1 = 100, // disable first IMU (for IMU failure testing)
KILL_IMU2 = 101, // disable second IMU (for IMU failure testing)
CAM_MODE_TOGGLE = 102, // Momentary switch to cycle camera modes
EKF_LANE_SWITCH = 103, // trigger lane switch attempt
EKF_YAW_RESET = 104, // trigger yaw reset attempt
// if you add something here, make sure to update the documentation of the parameter in RC_Channel.cpp!
// also, if you add an option >255, you will need to fix duplicate_options_exist