From 7301a8bddd44d055b33681912878df4f9228fbde Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 12 Dec 2011 22:08:10 +1100 Subject: [PATCH] pysim: added rotational resistance --- Tools/autotest/pysim/quadcopter.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Tools/autotest/pysim/quadcopter.py b/Tools/autotest/pysim/quadcopter.py index 60fb398395..48f29bdf16 100755 --- a/Tools/autotest/pysim/quadcopter.py +++ b/Tools/autotest/pysim/quadcopter.py @@ -12,6 +12,7 @@ class QuadCopter(Aircraft): self.mass = 1.0 # Kg self.hover_throttle = 0.37 self.terminal_velocity = 30.0 + self.terminal_rotation_rate = 4*360.0 self.frame_height = 0.1 # scaling from total motor power to Newtons. Allows the copter @@ -39,6 +40,11 @@ class QuadCopter(Aircraft): pitch_accel = (m[2] - m[3]) * 5000.0 yaw_accel = -((m[2]+m[3]) - (m[0]+m[1])) * 400.0 + # rotational resistance + roll_accel -= (self.pDeg / self.terminal_rotation_rate) * 5000.0 + pitch_accel -= (self.qDeg / self.terminal_rotation_rate) * 5000.0 + yaw_accel -= (self.rDeg / self.terminal_rotation_rate) * 400.0 + # update rotational rates in body frame self.pDeg += roll_accel * delta_time self.qDeg += pitch_accel * delta_time