mirror of https://github.com/ArduPilot/ardupilot
SITL: fixed the pwm output on startup
This commit is contained in:
parent
8b37790bd1
commit
d1713bd2fb
|
@ -197,9 +197,12 @@ static void sitl_simulator_output(void)
|
||||||
last_update = millis();
|
last_update = millis();
|
||||||
|
|
||||||
for (i=0; i<11; i++) {
|
for (i=0; i<11; i++) {
|
||||||
// the registers are 2x the PWM value
|
if (*reg[i] == 0xFFFF) {
|
||||||
|
pwm[i] = 0;
|
||||||
|
} else {
|
||||||
pwm[i] = (*reg[i])/2;
|
pwm[i] = (*reg[i])/2;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (!desktop_state.quadcopter) {
|
if (!desktop_state.quadcopter) {
|
||||||
// 400kV motor, 16V
|
// 400kV motor, 16V
|
||||||
|
|
Loading…
Reference in New Issue