mirror of https://github.com/ArduPilot/ardupilot
autotest: allow for negative col pitch in crrcsim heli
this allows for hovering upside down in acro mode
This commit is contained in:
parent
b0937154f5
commit
03b5305837
|
@ -33,7 +33,7 @@ class CRRCSim(Aircraft):
|
||||||
tail_rotor = servos[3]
|
tail_rotor = servos[3]
|
||||||
rsc = servos[7]
|
rsc = servos[7]
|
||||||
|
|
||||||
col_pitch = (swash1+swash2+swash3)/6.0
|
col_pitch = (swash1+swash2+swash3)/3.0 - 0.5
|
||||||
roll_rate = (swash1 - swash2)/2
|
roll_rate = (swash1 - swash2)/2
|
||||||
pitch_rate = -((swash1 + swash2)/2.0 - swash3)/2
|
pitch_rate = -((swash1 + swash2)/2.0 - swash3)/2
|
||||||
yaw_rate = -(tail_rotor - 0.5)
|
yaw_rate = -(tail_rotor - 0.5)
|
||||||
|
|
Loading…
Reference in New Issue