mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
APM: allow ailerons to move fully during servo demo
This commit is contained in:
parent
fcbd3a823b
commit
61f2e18e2e
@ -508,10 +508,13 @@ static void set_servos(void)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static bool demoing_servos;
|
||||||
|
|
||||||
static void demo_servos(byte i) {
|
static void demo_servos(byte i) {
|
||||||
|
|
||||||
while(i > 0) {
|
while(i > 0) {
|
||||||
gcs_send_text_P(SEVERITY_LOW,PSTR("Demo Servos!"));
|
gcs_send_text_P(SEVERITY_LOW,PSTR("Demo Servos!"));
|
||||||
|
demoing_servos = true;
|
||||||
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
#if HIL_MODE == HIL_MODE_DISABLED || HIL_SERVOS
|
||||||
APM_RC.OutputCh(1, 1400);
|
APM_RC.OutputCh(1, 1400);
|
||||||
mavlink_delay(400);
|
mavlink_delay(400);
|
||||||
@ -519,6 +522,7 @@ static void demo_servos(byte i) {
|
|||||||
mavlink_delay(200);
|
mavlink_delay(200);
|
||||||
APM_RC.OutputCh(1, 1500);
|
APM_RC.OutputCh(1, 1500);
|
||||||
#endif
|
#endif
|
||||||
|
demoing_servos = false;
|
||||||
mavlink_delay(400);
|
mavlink_delay(400);
|
||||||
i--;
|
i--;
|
||||||
}
|
}
|
||||||
|
@ -39,7 +39,11 @@ void failsafe_check(uint32_t tnow)
|
|||||||
// pass RC inputs to outputs every 20ms
|
// pass RC inputs to outputs every 20ms
|
||||||
last_timestamp = tnow;
|
last_timestamp = tnow;
|
||||||
APM_RC.clearOverride();
|
APM_RC.clearOverride();
|
||||||
for (uint8_t ch=0; ch<4; ch++) {
|
uint8_t start_ch = 0;
|
||||||
|
if (demoing_servos) {
|
||||||
|
start_ch = 1;
|
||||||
|
}
|
||||||
|
for (uint8_t ch=start_ch; ch<4; ch++) {
|
||||||
APM_RC.OutputCh(ch, APM_RC.InputCh(ch));
|
APM_RC.OutputCh(ch, APM_RC.InputCh(ch));
|
||||||
}
|
}
|
||||||
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual);
|
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual);
|
||||||
|
Loading…
Reference in New Issue
Block a user