mirror of https://github.com/ArduPilot/ardupilot
changed read_pwm to read
git-svn-id: https://arducopter.googlecode.com/svn/trunk@480 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
b7778b2ad9
commit
f4b024f194
|
@ -99,7 +99,7 @@ APM2_RC::init()
|
|||
// trim out the radio
|
||||
for(int c = 0; c < 50; c++){
|
||||
delay(20);
|
||||
read_pwm();
|
||||
read();
|
||||
}
|
||||
|
||||
trim();
|
||||
|
@ -109,7 +109,7 @@ APM2_RC::init()
|
|||
}
|
||||
}
|
||||
|
||||
void APM2_RC::read_pwm()
|
||||
void APM2_RC::read()
|
||||
{
|
||||
//Serial.print("ch1 in ");
|
||||
//Serial.print(raw[CH1],DEC);
|
||||
|
@ -189,7 +189,7 @@ APM2_RC::trim()
|
|||
{
|
||||
uint8_t temp = _mix_mode;
|
||||
_mix_mode = 0;
|
||||
read_pwm();
|
||||
read();
|
||||
_mix_mode = temp;
|
||||
|
||||
// Store the trim values
|
||||
|
|
|
@ -10,7 +10,7 @@ class APM2_RC : public RC
|
|||
public:
|
||||
APM2_RC();
|
||||
void init();
|
||||
void read_pwm();
|
||||
void read();
|
||||
void output();
|
||||
void set_ch_pwm(uint8_t ch, uint16_t pwm);
|
||||
void trim();
|
||||
|
|
|
@ -75,7 +75,7 @@ AP_RC::init()
|
|||
// trim out the radio
|
||||
for(int c = 0; c < 50; c++){
|
||||
delay(20);
|
||||
read_pwm();
|
||||
read();
|
||||
}
|
||||
|
||||
trim();
|
||||
|
@ -90,7 +90,7 @@ AP_RC::init()
|
|||
}
|
||||
|
||||
void
|
||||
AP_RC::read_pwm()
|
||||
AP_RC::read()
|
||||
{
|
||||
if((_direction_mask & 1) == 0 )
|
||||
timer1diff = REVERSE - timer1diff;
|
||||
|
@ -163,7 +163,7 @@ AP_RC::trim()
|
|||
{
|
||||
uint8_t temp = _mix_mode;
|
||||
_mix_mode = 0;
|
||||
read_pwm();
|
||||
read();
|
||||
_mix_mode = temp;
|
||||
|
||||
radio_trim[CH1] = radio_in[CH1];
|
||||
|
|
|
@ -10,7 +10,7 @@ class AP_RC : public RC
|
|||
public:
|
||||
AP_RC();
|
||||
void init();
|
||||
void read_pwm();
|
||||
void read();
|
||||
void output();
|
||||
void set_ch_pwm(uint8_t ch, uint16_t pwm);
|
||||
void trim();
|
||||
|
|
|
@ -24,7 +24,7 @@ class RC
|
|||
// RC();
|
||||
virtual void init();
|
||||
virtual void trim();
|
||||
virtual void read_pwm();
|
||||
virtual void read();
|
||||
virtual void output();
|
||||
virtual void set_channel_direction(uint8_t ch, int8_t dir);
|
||||
virtual void set_ch_pwm(uint8_t ch, uint16_t pwm);
|
||||
|
|
Loading…
Reference in New Issue