RC_Channel: add aux function for visodom-calibrate

This commit is contained in:
Randy Mackay 2020-03-29 09:24:48 +09:00
parent 9769f08fd9
commit 2f5a8fd6b9
2 changed files with 14 additions and 0 deletions

View File

@ -41,6 +41,7 @@ extern const AP_HAL::HAL& hal;
#include <AP_Avoidance/AP_Avoidance.h>
#include <AP_GPS/AP_GPS.h>
#include <AC_Fence/AC_Fence.h>
#include <AP_VisualOdom/AP_VisualOdom.h>
#define SWITCH_DEBOUNCE_TIME_MS 200
@ -462,6 +463,7 @@ void RC_Channel::init_aux_function(const aux_func_t ch_option, const aux_switch_
case AUX_FUNC::RELAY4:
case AUX_FUNC::RELAY5:
case AUX_FUNC::RELAY6:
case AUX_FUNC::VISODOM_CALIBRATE:
break;
case AUX_FUNC::AVOID_ADSB:
case AUX_FUNC::AVOID_PROXIMITY:
@ -884,6 +886,17 @@ void RC_Channel::do_aux_function(const aux_func_t ch_option, const aux_switch_po
}
break;
case AUX_FUNC::VISODOM_CALIBRATE:
#if HAL_VISUALODOM_ENABLED
if (ch_flag == HIGH) {
AP_VisualOdom *visual_odom = AP::visualodom();
if (visual_odom != nullptr) {
visual_odom->align_sensor_to_vehicle();
}
}
#endif
break;
#if !HAL_MINIMIZE_FEATURES
case AUX_FUNC::KILL_IMU1:
if (ch_flag == HIGH) {

View File

@ -177,6 +177,7 @@ public:
TAKEOFF = 77, // takeoff
RUNCAM_CONTROL = 78, // control RunCam device
RUNCAM_OSD_CONTROL = 79, // control RunCam OSD
VISODOM_CALIBRATE = 80, // calibrate visual odometry camera's attitude
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