Commit 9ba6018
committed
ArduCopter: fix MAV_CMD_DO_ORBIT double speed bug
orbit_run() was calling update_ms() twice per loop iteration:
once before the turn-count check and once after. Each call
advances the circle angle and ramps angular velocity, resulting
in exactly 2x the requested speed. Fix by removing the redundant
first call and keeping only the single update_ms(0.0f) call
before the attitude/position controller update.1 parent aebddf1 commit 9ba6018
1 file changed
Lines changed: 1 addition & 4 deletions
| Original file line number | Diff line number | Diff line change | |
|---|---|---|---|
| |||
1358 | 1358 | | |
1359 | 1359 | | |
1360 | 1360 | | |
1361 | | - | |
1362 | | - | |
| 1361 | + | |
1363 | 1362 | | |
1364 | 1363 | | |
1365 | 1364 | | |
| |||
1370 | 1369 | | |
1371 | 1370 | | |
1372 | 1371 | | |
1373 | | - | |
1374 | 1372 | | |
1375 | | - | |
1376 | 1373 | | |
1377 | 1374 | | |
1378 | 1375 | | |
| |||
0 commit comments