def calcForce(self, boatRelativeWaterAngle: Rotation2d, waterVelocity) -> Vector2d: """ :param boatRelativeWaterAngle: Angle of water current, relative to boat :param waterVelocity: Magnitude of water current, relative to boat :return: Boat oriented impulse vector direction + magnitude, in newtons """ aoa = abs(self._angle.degrees - boatRelativeWaterAngle.degrees) * unit.degree cL, cD = getCl(aoa), getCd(aoa) lift = calcLift_Water(waterVelocity=waterVelocity, foilArea=self.area, cl=cL).to(unit.newton) forceDir = self._angle.normal torqueSign = None if aoa == 0: torqueSign = 0 elif (self._angle.degrees - boatRelativeWaterAngle.degrees) > 0: torqueSign = 1 else: torqueSign = -1 lift *= torqueSign if (lift.m < 0): lift *= -1 forceDir = forceDir.rotateBy(Rotation2d.fromDegrees(180.0)) ret = Vector2d(0.0, 0.0) ret.x = forceDir.cos * lift ret.y = forceDir.sin * lift return ret
class Rudder: width = 6 * unit.inch height = 2 * unit.foot _angle = Rotation2d(1.0, 0.0) # [1 0] is inline with boat hull angleRangeDegrees = [-45, 45] def __init__(self): self.area = self.width * self.height @property def angle(self): return self._angle @angle.setter def angle(self, new: Rotation2d): self._angle = Rotation2d.fromDegrees( max(self.angleRangeDegrees[0], min(self.angleRangeDegrees[-1], new.degrees))) def calcForce(self, boatRelativeWaterAngle: Rotation2d, waterVelocity) -> Vector2d: """ :param boatRelativeWaterAngle: Angle of water current, relative to boat :param waterVelocity: Magnitude of water current, relative to boat :return: Boat oriented impulse vector direction + magnitude, in newtons """ aoa = abs(self._angle.degrees - boatRelativeWaterAngle.degrees) * unit.degree cL, cD = getCl(aoa), getCd(aoa) lift = calcLift_Water(waterVelocity=waterVelocity, foilArea=self.area, cl=cL).to(unit.newton) forceDir = self._angle.normal torqueSign = None if aoa == 0: torqueSign = 0 elif (self._angle.degrees - boatRelativeWaterAngle.degrees) > 0: torqueSign = 1 else: torqueSign = -1 lift *= torqueSign if (lift.m < 0): lift *= -1 forceDir = forceDir.rotateBy(Rotation2d.fromDegrees(180.0)) ret = Vector2d(0.0, 0.0) ret.x = forceDir.cos * lift ret.y = forceDir.sin * lift return ret
class Boat: orientation = RigidTransform2d( Translation2d(0.0 * unit.meter, 0.0 * unit.meter), Rotation2d(1.0, 0.0)) # Boat relative ([1.0, 0.0] is always 1 m/s forwards) velocity = Vector2d(0.0 * unit.meter / unit.second, 0.0 * unit.meter / unit.second) angularVelocity = 0 * unit.radian / unit.second MOI = 10 * unit.kg * unit.meter**2 fwdCrossSectionArea = 1 * unit.foot * 2 * unit.foot sideCrossSectionArea = 8 * unit.foot * 2 * unit.foot sail = Sail() rudder = Rudder() forwardCd = 0.15 sideCd = 1.2 viscFriction = 1e1 * unit.newton * unit.meter * unit.second def __init__(self): pass @property def spankerAngle(self): return self.sail.trailingEdgeAngle @spankerAngle.setter def spankerAngle(self, newAngle: Rotation2d): self.sail.trailingEdgeAngle = newAngle @property def rudderAngle(self): return self.rudder.angle @rudderAngle.setter def rudderAngle(self, newAngle: Rotation2d): self.rudder.angle = newAngle def update(self, *, dt): forceFromSail = self.sail.update( dt=dt, boatRelativeWindAngle=Wind.angle.rotateBy( self.orientation.rot.rotation))
class Wind: angle = Rotation2d(1.0, 0.0)
def angle(self, new: Rotation2d): self._angle = Rotation2d.fromDegrees( max(self.angleRangeDegrees[0], min(self.angleRangeDegrees[-1], new.degrees)))
foilArea=self.area, cl=cL).to(unit.newton) forceDir = self._angle.normal torqueSign = None if aoa == 0: torqueSign = 0 elif (self._angle.degrees - boatRelativeWaterAngle.degrees) > 0: torqueSign = 1 else: torqueSign = -1 lift *= torqueSign if (lift.m < 0): lift *= -1 forceDir = forceDir.rotateBy(Rotation2d.fromDegrees(180.0)) ret = Vector2d(0.0, 0.0) ret.x = forceDir.cos * lift ret.y = forceDir.sin * lift return ret if __name__ == '__main__': rudder = Rudder() rudder.angle = Rotation2d(1.0, 0.0).rotateBy(Rotation2d.fromDegrees(10)) print( rudder.calcForce(boatRelativeWaterAngle=Rotation2d(1.0, 0.0), waterVelocity=(1 * unit.m / unit.s)))
def update(self, dt, boatRelativeWindAngle: Rotation2d, boatRelativeWindSpeed) -> Vector2d: """ :param dt: Update delta time, in seconds :param boatRelativeWindAngle: Wind angle relative to boat ([-1 0] is a headwind) :param boatRelativeWindSpeed: Wind strength, in m/s :return: Boat oriented impulse vector direction + magnitude, in newtons """ # Calculate angle of attack of sails to get the coefficient of lift and drag mainSailAoA = abs(self.mainSail.relativeHeading # .rotateBy(boatHeading) .degrees - boatRelativeWindAngle.degrees) * unit.degree ancillarySailAoA = abs( self.ancillarySail.relativeHeading.rotateBy( self.mainSail.relativeHeading) # .rotateBy(boatHeading) .degrees - boatRelativeWindAngle.degrees) * unit.degree mainCl, mainCd = getCl(mainSailAoA), getCd(mainSailAoA) ancillaryCl, ancillaryCd = getCl(ancillarySailAoA), getCd( ancillarySailAoA) # Calculate effective area of the side (pushy bit) of the sail that the wind's hitting. Not necessary now, might be later (for drag). # mainSailSidePresentedArea = self.mainSail.sideArea * \ # self._calcSailPercentExposed(boatRelativeWindAngle, # self.mainSail # .relativeHeading # # .rotateBy(boatHeading) # .normal) # ancillarySailSidePresentedArea = self.ancillarySail.sideArea * \ # self._calcSailPercentExposed(boatRelativeWindAngle, # self.ancillarySail # .relativeHeading # .rotateBy(self.mainSail.relativeHeading) # # .rotateBy(boatHeading) # .normal) mainSailLift = calcLift_Air(airVelocity=boatRelativeWindSpeed, wingArea=self.mainSail.sideArea, cl=mainCl) ancillarySailLift = calcLift_Air(airVelocity=boatRelativeWindSpeed, wingArea=self.ancillarySail.sideArea, cl=ancillaryCl) # print(mainSailLift.to(unit.newton)) # print(ancillarySailLift.to(unit.newton)) # AoA is side invarient, now we need to figure out which way our force is actually applied mainSailForce = mainSailLift.to(unit.newton) forceOnBoatDirection = None if mainSailAoA == 0: forceOnBoatDirection = self.mainSail.relativeHeading mainSailForce = 0 * unit.newton elif self.mainSail.relativeHeading.degrees - boatRelativeWindAngle.degrees > 0: forceOnBoatDirection = self.mainSail.relativeHeading.normal else: forceOnBoatDirection = self.mainSail.relativeHeading.normal.rotateBy( Rotation2d.fromDegrees(180.0)) # Same deal, but just a torque multiplier this time, since the sail assembly can only pivot and not translate xy ancillarySailForce = ancillarySailLift.to(unit.newton) torqueSign = None if ancillarySailAoA == 0: torqueSign = 0 elif self.ancillarySail.relativeHeading \ .rotateBy(self.mainSail.relativeHeading).degrees - boatRelativeWindAngle.degrees > 0: torqueSign = -1 else: torqueSign = 1 # Now we have to calculate the torque that the ancillary sail puts out on the sail assembly torque = (self.ancillarySail.pivotOffset * ancillarySailForce * torqueSign).to(unit.newton * unit.meter) angularAcceleration = (torque - self.mainSail.angularVelocity * self.mainSail.ViscFriction) / self.mainSail.MOI # t' = -tb/J self.mainSail.angularVelocity += angularAcceleration * dt self.mainSail.relativeHeading = self.mainSail.relativeHeading \ .rotateBy( Rotation2d.fromDegrees( (self.mainSail.angularVelocity * dt).to(unit.degrees).m ) ) ret = Vector2d(0.0, 0.0) ret.x = forceOnBoatDirection.cos * mainSailForce ret.y = forceOnBoatDirection.sin * mainSailForce return ret
class Sail: # NACA 0012 airfoil mainSail = SimpleNamespace(width=1 * unit.foot, height=5 * unit.foot, thicc=4 * unit.inch, sideCoD=1.25, frontCoD=0.6, relativeHeading=Rotation2d(1.0, 0.0), angularVelocity=0.0 * unit.radian / unit.second, MOI=0.50 * unit.kg * (unit.meter**2), ViscFriction=1e-0 * unit.newton * unit.meter * unit.second) # NACA 0012 airfoil ancillarySail = SimpleNamespace(width=6 * unit.inch, height=3 * unit.foot, thicc=4 * unit.inch, pivotOffset=3 * unit.foot, sideCoD=1.25, frontCoD=0.6, relativeHeading=Rotation2d(1.0, 0.0), maxAngle=Rotation2d.fromDegrees(45), minAngle=Rotation2d.fromDegrees(-45)) def __init__(self): self.mainSail.sideArea = self.mainSail.width * self.mainSail.height self.ancillarySail.sideArea = self.ancillarySail.width * self.ancillarySail.height self.mainSail.frontArea = self.mainSail.thicc * self.mainSail.height self.ancillarySail.frontArea = self.ancillarySail.thicc * self.ancillarySail.height @property def trailingEdgeAngle(self): return self.ancillarySail.relativeHeading @trailingEdgeAngle.setter def trailingEdgeAngle(self, newAngle: Rotation2d): assert self.ancillarySail.minAngle < newAngle.degrees < self.ancillarySail.maxAngle self.ancillarySail.relativeHeading = newAngle def _calcSailPercentExposed(self, boatRelativeWindAngle: Rotation2d, sailAngle: Rotation2d) -> float: """ :param boatRelativeWindAngle: Angle of wind relative to boat :param sailAngle: Angle of sail relative to boat :return: Percent of sail that's exposed to wind (as the angle of attack becomes smaller, less is exposed) """ return boatRelativeWindAngle.rotation.dot(sailAngle.rotation) def update(self, dt, boatRelativeWindAngle: Rotation2d, boatRelativeWindSpeed) -> Vector2d: """ :param dt: Update delta time, in seconds :param boatRelativeWindAngle: Wind angle relative to boat ([-1 0] is a headwind) :param boatRelativeWindSpeed: Wind strength, in m/s :return: Boat oriented impulse vector direction + magnitude, in newtons """ # Calculate angle of attack of sails to get the coefficient of lift and drag mainSailAoA = abs(self.mainSail.relativeHeading # .rotateBy(boatHeading) .degrees - boatRelativeWindAngle.degrees) * unit.degree ancillarySailAoA = abs( self.ancillarySail.relativeHeading.rotateBy( self.mainSail.relativeHeading) # .rotateBy(boatHeading) .degrees - boatRelativeWindAngle.degrees) * unit.degree mainCl, mainCd = getCl(mainSailAoA), getCd(mainSailAoA) ancillaryCl, ancillaryCd = getCl(ancillarySailAoA), getCd( ancillarySailAoA) # Calculate effective area of the side (pushy bit) of the sail that the wind's hitting. Not necessary now, might be later (for drag). # mainSailSidePresentedArea = self.mainSail.sideArea * \ # self._calcSailPercentExposed(boatRelativeWindAngle, # self.mainSail # .relativeHeading # # .rotateBy(boatHeading) # .normal) # ancillarySailSidePresentedArea = self.ancillarySail.sideArea * \ # self._calcSailPercentExposed(boatRelativeWindAngle, # self.ancillarySail # .relativeHeading # .rotateBy(self.mainSail.relativeHeading) # # .rotateBy(boatHeading) # .normal) mainSailLift = calcLift_Air(airVelocity=boatRelativeWindSpeed, wingArea=self.mainSail.sideArea, cl=mainCl) ancillarySailLift = calcLift_Air(airVelocity=boatRelativeWindSpeed, wingArea=self.ancillarySail.sideArea, cl=ancillaryCl) # print(mainSailLift.to(unit.newton)) # print(ancillarySailLift.to(unit.newton)) # AoA is side invarient, now we need to figure out which way our force is actually applied mainSailForce = mainSailLift.to(unit.newton) forceOnBoatDirection = None if mainSailAoA == 0: forceOnBoatDirection = self.mainSail.relativeHeading mainSailForce = 0 * unit.newton elif self.mainSail.relativeHeading.degrees - boatRelativeWindAngle.degrees > 0: forceOnBoatDirection = self.mainSail.relativeHeading.normal else: forceOnBoatDirection = self.mainSail.relativeHeading.normal.rotateBy( Rotation2d.fromDegrees(180.0)) # Same deal, but just a torque multiplier this time, since the sail assembly can only pivot and not translate xy ancillarySailForce = ancillarySailLift.to(unit.newton) torqueSign = None if ancillarySailAoA == 0: torqueSign = 0 elif self.ancillarySail.relativeHeading \ .rotateBy(self.mainSail.relativeHeading).degrees - boatRelativeWindAngle.degrees > 0: torqueSign = -1 else: torqueSign = 1 # Now we have to calculate the torque that the ancillary sail puts out on the sail assembly torque = (self.ancillarySail.pivotOffset * ancillarySailForce * torqueSign).to(unit.newton * unit.meter) angularAcceleration = (torque - self.mainSail.angularVelocity * self.mainSail.ViscFriction) / self.mainSail.MOI # t' = -tb/J self.mainSail.angularVelocity += angularAcceleration * dt self.mainSail.relativeHeading = self.mainSail.relativeHeading \ .rotateBy( Rotation2d.fromDegrees( (self.mainSail.angularVelocity * dt).to(unit.degrees).m ) ) ret = Vector2d(0.0, 0.0) ret.x = forceOnBoatDirection.cos * mainSailForce ret.y = forceOnBoatDirection.sin * mainSailForce return ret
self.mainSail.relativeHeading = self.mainSail.relativeHeading \ .rotateBy( Rotation2d.fromDegrees( (self.mainSail.angularVelocity * dt).to(unit.degrees).m ) ) ret = Vector2d(0.0, 0.0) ret.x = forceOnBoatDirection.cos * mainSailForce ret.y = forceOnBoatDirection.sin * mainSailForce return ret if __name__ == '__main__': sail = Sail() sail.mainSail.relativeHeading = Rotation2d.fromDegrees(0) sail.ancillarySail.relativeHeading = Rotation2d.fromDegrees(30) X, Y = [], [] dt = 0.01 for i in range(1000): try: sail.update( dt * unit.second, boatRelativeWindAngle=Rotation2d(1.0, 0.0), boatRelativeWindSpeed=5 * unit.meter / unit.second, ) X.append(i * dt) Y.append(sail.mainSail.relativeHeading.degrees) except: break