Rover: move from AUX_FUNC::SAVE_TRIM to AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC

This commit is contained in:
Iampete1 2021-09-21 22:18:25 +01:00 committed by Andrew Tridgell
parent 3d566ca59b
commit 6ebef3fe6b
2 changed files with 3 additions and 2 deletions

View File

@ -45,7 +45,7 @@ void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSw
case AUX_FUNC::WALKING_HEIGHT:
case AUX_FUNC::RTL:
case AUX_FUNC::SAILBOAT_TACK:
case AUX_FUNC::SAVE_TRIM:
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
case AUX_FUNC::SAVE_WP:
case AUX_FUNC::SIMPLE:
case AUX_FUNC::SMART_RTL:
@ -230,7 +230,7 @@ bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
break;
// save steering trim
case AUX_FUNC::SAVE_TRIM:
case AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC:
if (!rover.g2.motors.have_skid_steering() && rover.arming.is_armed() &&
(rover.control_mode != &rover.mode_loiter)
&& (rover.control_mode != &rover.mode_hold) && ch_flag == AuxSwitchPos::HIGH) {

View File

@ -131,6 +131,7 @@ void Rover::init_ardupilot()
// initialise rc channels
rc().convert_options(RC_Channel::AUX_FUNC::ARMDISARM_UNUSED, RC_Channel::AUX_FUNC::ARMDISARM);
rc().convert_options(RC_Channel::AUX_FUNC::SAVE_TRIM, RC_Channel::AUX_FUNC::TRIM_TO_CURRENT_SERVO_RC);
rc().init();
rover.g2.sailboat.init();