From b3c9cdb353a9f1a193e94cac435107e684a98622 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 4 Jul 2012 15:59:15 +1000 Subject: [PATCH] SITL: fixed the normalisation of the DCM matrix in the multicopter sim --- Tools/autotest/pysim/multicopter.py | 1 + 1 file changed, 1 insertion(+) diff --git a/Tools/autotest/pysim/multicopter.py b/Tools/autotest/pysim/multicopter.py index 3447189271..a5955e5182 100755 --- a/Tools/autotest/pysim/multicopter.py +++ b/Tools/autotest/pysim/multicopter.py @@ -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)