mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: RC_Channel add sailboat motor aux functions
This commit is contained in:
parent
fdb6da0793
commit
54f3173c7c
@ -45,6 +45,10 @@ void RC_Channel_Rover::init_aux_function(const aux_func_t ch_option, const aux_s
|
|||||||
case AUX_FUNC::LOITER:
|
case AUX_FUNC::LOITER:
|
||||||
case AUX_FUNC::FOLLOW:
|
case AUX_FUNC::FOLLOW:
|
||||||
case AUX_FUNC::SAILBOAT_TACK:
|
case AUX_FUNC::SAILBOAT_TACK:
|
||||||
|
case AUX_FUNC::MAINSAIL:
|
||||||
|
break;
|
||||||
|
case AUX_FUNC::SAILBOAT_MOTOR_3POS:
|
||||||
|
do_aux_function_sailboat_motor_3pos(ch_flag);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
RC_Channel::init_aux_function(ch_option, ch_flag);
|
RC_Channel::init_aux_function(ch_option, ch_flag);
|
||||||
@ -95,6 +99,21 @@ void RC_Channel_Rover::add_waypoint_for_current_loc()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void RC_Channel_Rover::do_aux_function_sailboat_motor_3pos(const aux_switch_pos_t ch_flag)
|
||||||
|
{
|
||||||
|
switch(ch_flag) {
|
||||||
|
case HIGH:
|
||||||
|
rover.g2.sailboat.throttle_state = rover.g2.sailboat.Sailboat_Throttle::FORCE_MOTOR;
|
||||||
|
break;
|
||||||
|
case MIDDLE:
|
||||||
|
rover.g2.sailboat.throttle_state = rover.g2.sailboat.Sailboat_Throttle::ASSIST;
|
||||||
|
break;
|
||||||
|
case LOW:
|
||||||
|
rover.g2.sailboat.throttle_state = rover.g2.sailboat.Sailboat_Throttle::NEVER;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
|
void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const aux_switch_pos_t ch_flag)
|
||||||
{
|
{
|
||||||
switch (ch_option) {
|
switch (ch_option) {
|
||||||
@ -195,6 +214,15 @@ void RC_Channel_Rover::do_aux_function(const aux_func_t ch_option, const aux_swi
|
|||||||
rover.control_mode->handle_tack_request();
|
rover.control_mode->handle_tack_request();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
// sailboat motor state 3pos
|
||||||
|
case AUX_FUNC::SAILBOAT_MOTOR_3POS:
|
||||||
|
do_aux_function_sailboat_motor_3pos(ch_flag);
|
||||||
|
break;
|
||||||
|
|
||||||
|
// mainsail input, nothing to do
|
||||||
|
case AUX_FUNC::MAINSAIL:
|
||||||
|
break;
|
||||||
|
|
||||||
default:
|
default:
|
||||||
RC_Channel::do_aux_function(ch_option, ch_flag);
|
RC_Channel::do_aux_function(ch_option, ch_flag);
|
||||||
break;
|
break;
|
||||||
|
@ -23,6 +23,8 @@ private:
|
|||||||
const aux_switch_pos_t ch_flag);
|
const aux_switch_pos_t ch_flag);
|
||||||
|
|
||||||
void add_waypoint_for_current_loc();
|
void add_waypoint_for_current_loc();
|
||||||
|
|
||||||
|
void do_aux_function_sailboat_motor_3pos(const aux_switch_pos_t ch_flag);
|
||||||
};
|
};
|
||||||
|
|
||||||
class RC_Channels_Rover : public RC_Channels
|
class RC_Channels_Rover : public RC_Channels
|
||||||
|
Loading…
Reference in New Issue
Block a user