mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Add twitch_servos required by ArduPilot.
git-svn-id: https://arducopter.googlecode.com/svn/trunk@504 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
29ba4b8be1
commit
3ea33576f6
@ -198,7 +198,7 @@ APM2_RC::trim()
|
|||||||
radio_trim[y] = radio_in[y];
|
radio_trim[y] = radio_in[y];
|
||||||
}
|
}
|
||||||
void
|
void
|
||||||
AP_RC::twitch_servos(void)
|
APM2_RC::twitch_servos(uint8_t times)
|
||||||
{
|
{
|
||||||
// todo
|
// todo
|
||||||
}
|
}
|
||||||
@ -324,4 +324,4 @@ void APM2_RC::force_out_6_7(void)
|
|||||||
if (TCNT3 > 5000)
|
if (TCNT3 > 5000)
|
||||||
TCNT3 = 39990;
|
TCNT3 = 39990;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -14,6 +14,7 @@ class APM2_RC : public RC
|
|||||||
void output();
|
void output();
|
||||||
void set_ch_pwm(uint8_t ch, uint16_t pwm);
|
void set_ch_pwm(uint8_t ch, uint16_t pwm);
|
||||||
void trim();
|
void trim();
|
||||||
|
void twitch_servos(uint8_t times);
|
||||||
|
|
||||||
void force_out_0_1(void);
|
void force_out_0_1(void);
|
||||||
void force_out_2_3(void);
|
void force_out_2_3(void);
|
||||||
|
@ -14,6 +14,7 @@ class AP_RC : public RC
|
|||||||
void output();
|
void output();
|
||||||
void set_ch_pwm(uint8_t ch, uint16_t pwm);
|
void set_ch_pwm(uint8_t ch, uint16_t pwm);
|
||||||
void trim();
|
void trim();
|
||||||
|
void twitch_servos(uint8_t times);
|
||||||
|
|
||||||
int16_t radio_in[4];
|
int16_t radio_in[4];
|
||||||
int16_t radio_min[4];
|
int16_t radio_min[4];
|
||||||
|
Loading…
Reference in New Issue
Block a user