mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/APM_RC/APM_RC_APM1.h
This commit is contained in:
parent
9365bf7126
commit
5af2e87786
|
@ -9,33 +9,33 @@
|
||||||
|
|
||||||
class APM_RC_APM1 : public APM_RC_Class
|
class APM_RC_APM1 : public APM_RC_Class
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
APM_RC_APM1();
|
APM_RC_APM1();
|
||||||
void Init( Arduino_Mega_ISR_Registry * isr_reg );
|
void Init( Arduino_Mega_ISR_Registry * isr_reg );
|
||||||
void OutputCh(uint8_t ch, uint16_t pwm);
|
void OutputCh(uint8_t ch, uint16_t pwm);
|
||||||
uint16_t OutputCh_current(uint8_t ch);
|
uint16_t OutputCh_current(uint8_t ch);
|
||||||
uint16_t InputCh(uint8_t ch);
|
uint16_t InputCh(uint8_t ch);
|
||||||
uint8_t GetState();
|
uint8_t GetState();
|
||||||
bool setHIL(int16_t v[NUM_CHANNELS]);
|
bool setHIL(int16_t v[NUM_CHANNELS]);
|
||||||
void clearOverride(void);
|
void clearOverride(void);
|
||||||
void Force_Out(void);
|
void Force_Out(void);
|
||||||
void SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz = 400);
|
void SetFastOutputChannels(uint32_t chmask, uint16_t speed_hz = 400);
|
||||||
|
|
||||||
void enable_out(uint8_t);
|
void enable_out(uint8_t);
|
||||||
void disable_out(uint8_t);
|
void disable_out(uint8_t);
|
||||||
|
|
||||||
void Force_Out0_Out1(void);
|
void Force_Out0_Out1(void);
|
||||||
void Force_Out2_Out3(void);
|
void Force_Out2_Out3(void);
|
||||||
void Force_Out6_Out7(void);
|
void Force_Out6_Out7(void);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
static void _timer4_capt_cb(void);
|
static void _timer4_capt_cb(void);
|
||||||
|
|
||||||
static volatile uint16_t _PWM_RAW[NUM_CHANNELS];
|
static volatile uint16_t _PWM_RAW[NUM_CHANNELS];
|
||||||
static volatile uint8_t _radio_status;
|
static volatile uint8_t _radio_status;
|
||||||
|
|
||||||
int16_t _HIL_override[NUM_CHANNELS];
|
int16_t _HIL_override[NUM_CHANNELS];
|
||||||
};
|
};
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue