mirror of https://github.com/ArduPilot/ardupilot
Rover: return MAV_RESULT_FAILED from do_aux_function if invalid function
This commit is contained in:
parent
cb8ca17035
commit
b245b027f7
|
@ -125,7 +125,7 @@ void RC_Channel_Rover::do_aux_function_sailboat_motor_3pos(const AuxSwitchPos ch
|
|||
}
|
||||
}
|
||||
|
||||
void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
|
||||
bool RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwitchPos ch_flag)
|
||||
{
|
||||
switch (ch_option) {
|
||||
case AUX_FUNC::DO_NOTHING:
|
||||
|
@ -134,7 +134,7 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
|||
if (ch_flag == AuxSwitchPos::HIGH) {
|
||||
// do nothing if in AUTO mode
|
||||
if (rover.control_mode == &rover.mode_auto) {
|
||||
return;
|
||||
break;
|
||||
}
|
||||
|
||||
// if disarmed clear mission and set home to current location
|
||||
|
@ -143,7 +143,7 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
|||
if (!rover.set_home_to_current_location(false)) {
|
||||
// ignored
|
||||
}
|
||||
return;
|
||||
break;
|
||||
}
|
||||
|
||||
// record the waypoint if not in auto mode
|
||||
|
@ -248,8 +248,9 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const AuxSwit
|
|||
break;
|
||||
|
||||
default:
|
||||
RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
break;
|
||||
return RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -12,7 +12,7 @@ public:
|
|||
protected:
|
||||
|
||||
void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
|
||||
void do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
|
||||
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
|
||||
|
||||
// called when the mode switch changes position:
|
||||
void mode_switch_changed(modeswitch_pos_t new_pos) override;
|
||||
|
|
Loading…
Reference in New Issue