mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/APM_RC/APM_RC.h
This commit is contained in:
parent
5af2e87786
commit
0234d70511
|
@ -32,25 +32,27 @@ class APM_RC_Class
|
|||
|
||||
{
|
||||
|
||||
public:
|
||||
public:
|
||||
|
||||
virtual void Init( Arduino_Mega_ISR_Registry * isr_reg ) = 0;
|
||||
virtual void OutputCh(uint8_t ch, uint16_t pwm) = 0;
|
||||
virtual uint16_t OutputCh_current(uint8_t ch) = 0;
|
||||
virtual uint16_t InputCh(uint8_t ch) = 0;
|
||||
virtual uint8_t GetState() = 0;
|
||||
virtual void clearOverride(void) = 0;
|
||||
virtual void Force_Out() = 0;
|
||||
virtual void SetFastOutputChannels( uint32_t channelmask, uint16_t speed_hz = 400 ) = 0;
|
||||
virtual void enable_out(uint8_t) = 0;
|
||||
virtual void disable_out(uint8_t) = 0;
|
||||
virtual void Init( Arduino_Mega_ISR_Registry * isr_reg ) = 0;
|
||||
virtual void OutputCh(uint8_t ch, uint16_t pwm) = 0;
|
||||
virtual uint16_t OutputCh_current(uint8_t ch) = 0;
|
||||
virtual uint16_t InputCh(uint8_t ch) = 0;
|
||||
virtual uint8_t GetState() = 0;
|
||||
virtual void clearOverride(void) = 0;
|
||||
virtual void Force_Out() = 0;
|
||||
virtual void SetFastOutputChannels( uint32_t channelmask, uint16_t speed_hz = 400 ) = 0;
|
||||
virtual void enable_out(uint8_t) = 0;
|
||||
virtual void disable_out(uint8_t) = 0;
|
||||
|
||||
virtual void Force_Out0_Out1(void) = 0;
|
||||
virtual void Force_Out2_Out3(void) = 0;
|
||||
virtual void Force_Out6_Out7(void) = 0;
|
||||
virtual void Force_Out0_Out1(void) = 0;
|
||||
virtual void Force_Out2_Out3(void) = 0;
|
||||
virtual void Force_Out6_Out7(void) = 0;
|
||||
|
||||
protected:
|
||||
uint16_t _map_speed(uint16_t speed_hz) { return 2000000UL / speed_hz; }
|
||||
uint16_t _map_speed(uint16_t speed_hz) {
|
||||
return 2000000UL / speed_hz;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue