mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
RC_Channel: adjust type for auxillary switch position
This commit is contained in:
parent
ecb3cabf72
commit
87aeaf7315
@ -180,15 +180,13 @@ public:
|
||||
|
||||
protected:
|
||||
|
||||
// auxillary switch handling:
|
||||
enum aux_switch_pos {
|
||||
// auxillary switch handling (n.b.: we store this as 2-bits!):
|
||||
enum aux_switch_pos_t : uint8_t {
|
||||
LOW, // indicates auxiliary switch is in the low position (pwm <1200)
|
||||
MIDDLE, // indicates auxiliary switch is in the middle position (pwm >1200, <1800)
|
||||
HIGH // indicates auxiliary switch is in the high position (pwm >1800)
|
||||
};
|
||||
|
||||
typedef enum aux_switch_pos aux_switch_pos_t;
|
||||
|
||||
virtual void init_aux_function(aux_func_t ch_option, aux_switch_pos_t);
|
||||
virtual void do_aux_function(aux_func_t ch_option, aux_switch_pos_t);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user