Rover: rc_channel inits roll and pitch input channels

This commit is contained in:
Peter Hall 2020-01-26 17:24:51 +00:00 committed by Randy Mackay
parent d5316edde7
commit 2d4deb505d
1 changed files with 8 additions and 4 deletions

View File

@ -42,6 +42,8 @@ void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const AuxSw
case AUX_FUNC::LOITER: case AUX_FUNC::LOITER:
case AUX_FUNC::MAINSAIL: case AUX_FUNC::MAINSAIL:
case AUX_FUNC::MANUAL: case AUX_FUNC::MANUAL:
case AUX_FUNC::PITCH:
case AUX_FUNC::ROLL:
case AUX_FUNC::RTL: case AUX_FUNC::RTL:
case AUX_FUNC::SAILBOAT_TACK: case AUX_FUNC::SAILBOAT_TACK:
case AUX_FUNC::SAVE_TRIM: case AUX_FUNC::SAVE_TRIM:
@ -227,10 +229,6 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
do_aux_function_sailboat_motor_3pos(ch_flag); do_aux_function_sailboat_motor_3pos(ch_flag);
break; break;
// mainsail input, nothing to do
case AUX_FUNC::MAINSAIL:
break;
// save steering trim // save steering trim
case AUX_FUNC::SAVE_TRIM: case AUX_FUNC::SAVE_TRIM:
if (!rover.g2.motors.have_skid_steering() && rover.arming.is_armed() && if (!rover.g2.motors.have_skid_steering() && rover.arming.is_armed() &&
@ -241,6 +239,12 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
} }
break; break;
// manual input, nothing to do
case AUX_FUNC::MAINSAIL:
case AUX_FUNC::PITCH:
case AUX_FUNC::ROLL:
break;
default: default:
RC_Channel::do_aux_function(ch_option, ch_flag); RC_Channel::do_aux_function(ch_option, ch_flag);
break; break;