mirror of https://github.com/ArduPilot/ardupilot
pysim: added rotational resistance
This commit is contained in:
parent
ef8ed6aab2
commit
7301a8bddd
|
@ -12,6 +12,7 @@ class QuadCopter(Aircraft):
|
||||||
self.mass = 1.0 # Kg
|
self.mass = 1.0 # Kg
|
||||||
self.hover_throttle = 0.37
|
self.hover_throttle = 0.37
|
||||||
self.terminal_velocity = 30.0
|
self.terminal_velocity = 30.0
|
||||||
|
self.terminal_rotation_rate = 4*360.0
|
||||||
self.frame_height = 0.1
|
self.frame_height = 0.1
|
||||||
|
|
||||||
# scaling from total motor power to Newtons. Allows the copter
|
# 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
|
pitch_accel = (m[2] - m[3]) * 5000.0
|
||||||
yaw_accel = -((m[2]+m[3]) - (m[0]+m[1])) * 400.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
|
# update rotational rates in body frame
|
||||||
self.pDeg += roll_accel * delta_time
|
self.pDeg += roll_accel * delta_time
|
||||||
self.qDeg += pitch_accel * delta_time
|
self.qDeg += pitch_accel * delta_time
|
||||||
|
|
Loading…
Reference in New Issue