mirror of https://github.com/ArduPilot/ardupilot
don't fly
git-svn-id: https://arducopter.googlecode.com/svn/trunk@426 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
parent
6268189d31
commit
5dc67ce6c6
|
@ -197,7 +197,11 @@ APM2_RC::trim()
|
|||
for (int y = 0; y < 8; y++)
|
||||
radio_trim[y] = radio_in[y];
|
||||
}
|
||||
|
||||
void
|
||||
AP_RC::twitch_servos(void)
|
||||
{
|
||||
// todo
|
||||
}
|
||||
void
|
||||
APM2_RC::set_ch_pwm(uint8_t ch, uint16_t pwm)
|
||||
{
|
||||
|
|
|
@ -175,11 +175,23 @@ AP_RC::trim()
|
|||
//Serial.println(radio_trim[CH1], DEC);
|
||||
}
|
||||
|
||||
/*void
|
||||
AP_RC::set_throttle(float percent)
|
||||
void
|
||||
AP_RC::twitch_servos(uint8_t times)
|
||||
{
|
||||
while (times > 0){
|
||||
set_ch_pwm(CH1, radio_trim[CH1] + 100);
|
||||
set_ch_pwm(CH2, radio_trim[CH2] + 100);
|
||||
delay(400);
|
||||
set_ch_pwm(CH1, radio_trim[CH1] - 100);
|
||||
set_ch_pwm(CH2, radio_trim[CH2] - 100);
|
||||
delay(200);
|
||||
set_ch_pwm(CH1, radio_trim[CH1]);
|
||||
set_ch_pwm(CH2, radio_trim[CH2]);
|
||||
delay(30);
|
||||
times--;
|
||||
}
|
||||
}
|
||||
*/
|
||||
|
||||
void
|
||||
AP_RC::set_ch_pwm(uint8_t ch, uint16_t pwm)
|
||||
{
|
||||
|
|
|
@ -28,6 +28,7 @@ class RC
|
|||
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);
|
||||
virtual void twitch_servos(void);
|
||||
|
||||
void set_failsafe(uint16_t fs);
|
||||
void set_mix_mode(uint8_t mode);
|
||||
|
|
Loading…
Reference in New Issue