forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 6
/
RC_Channel.h
53 lines (36 loc) · 1.31 KB
/
RC_Channel.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
#pragma once
#include <RC_Channel/RC_Channel.h>
#include <AP_Motors/AP_Motors.h>
#include "mode.h"
class RC_Channel_Copter : public RC_Channel
{
public:
protected:
void init_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
bool do_aux_function(aux_func_t ch_option, AuxSwitchPos) override;
private:
void do_aux_function_change_mode(const Mode::Number mode,
const AuxSwitchPos ch_flag);
void do_aux_function_change_air_mode(const AuxSwitchPos ch_flag);
void do_aux_function_change_force_flying(const AuxSwitchPos ch_flag);
// called when the mode switch changes position:
void mode_switch_changed(modeswitch_pos_t new_pos) override;
};
class RC_Channels_Copter : public RC_Channels
{
public:
bool has_valid_input() const override;
bool in_rc_failsafe() const override;
RC_Channel *get_arming_channel(void) const override;
RC_Channel_Copter obj_channels[NUM_RC_CHANNELS];
RC_Channel_Copter *channel(const uint8_t chan) override {
if (chan >= NUM_RC_CHANNELS) {
return nullptr;
}
return &obj_channels[chan];
}
// returns true if throttle arming checks should be run
bool arming_check_throttle() const override;
protected:
int8_t flight_mode_channel_number() const override;
};