mirror of https://github.com/ArduPilot/ardupilot
Made wind not reverse itself to be more natural
This commit is contained in:
parent
4b5437afe8
commit
a29aa020ff
|
@ -375,8 +375,7 @@ class Wind(object):
|
|||
w_delta = math.sqrt(deltat)*(1.0-random.gauss(1.0, self.turbulance))
|
||||
w_delta -= (self.turbulance_mul-1.0)*(deltat/self.turbulance_time_constant)
|
||||
self.turbulance_mul += w_delta
|
||||
|
||||
speed = self.speed * self.turbulance_mul
|
||||
speed = self.speed * math.fabs(self.turbulance_mul)
|
||||
return (speed, self.direction)
|
||||
|
||||
def accel(self, velocity, deltat=None):
|
||||
|
|
Loading…
Reference in New Issue