mirror of https://github.com/ArduPilot/ardupilot
SITL: fixed the normalisation of the DCM matrix in the multicopter sim
This commit is contained in:
parent
6cf2e2fa13
commit
b3c9cdb353
|
@ -132,6 +132,7 @@ class MultiCopter(Aircraft):
|
|||
|
||||
# update attitude
|
||||
self.dcm.rotate(self.gyro * delta_time)
|
||||
self.dcm.normalize()
|
||||
|
||||
# air resistance
|
||||
air_resistance = - self.velocity * (self.gravity/self.terminal_velocity)
|
||||
|
|
Loading…
Reference in New Issue