refactor: Combine Hirth Joint into one class

This commit is contained in:
Leni Aniva 2024-06-28 23:07:37 -04:00
parent 87e99ac4ce
commit 3170a025a1
Signed by: aniva
GPG Key ID: 4D9B1C8D10EA4C50
7 changed files with 237 additions and 195 deletions

6
nhf/checks.py Normal file
View File

@ -0,0 +1,6 @@
import cadquery as Cq
def binary_intersection(a: Cq.Assembly) -> Cq.Shape:
objs = [s.toCompound() for _, s in a.traverse() if isinstance(s, Cq.Assembly)]
obj1, obj2 = objs[:2]
return obj1.intersect(obj2)

View File

@ -10,156 +10,165 @@ def hirth_tooth_angle(n_tooth):
""" """
return 360 / n_tooth return 360 / n_tooth
def hirth_joint(radius=60, @dataclass(frozen=True)
radius_inner=40, class HirthJoint:
base_height=20,
n_tooth=16,
tooth_height=16,
tooth_height_inner=2,
tol=0.01,
tag_prefix="",
is_mated=False):
""" """
Creates a cylindrical Hirth Joint A Hirth joint attached to a cylindrical base
is_mated: If set to true, rotate the teeth so they line up at 0 degrees.
FIXME: The curves don't mate perfectly. See if non-planar lofts can solve
this issue.
""" """
# ensures tangent doesn't blow up radius: float = 60
assert n_tooth >= 5 radius_inner: float = 40
assert radius > radius_inner base_height: float = 20
assert tooth_height >= tooth_height_inner n_tooth: float = 16
tooth_height: float = 16
tooth_height_inner: float = 2
# angle of half of a single tooth def __post_init__(self):
theta = math.pi / n_tooth # Ensures tangent doesn't blow up
assert self.n_tooth >= 5
assert self.radius > self.radius_inner
assert self.tooth_height >= self.tooth_height_inner
c, s, t = math.cos(theta), math.sin(theta), math.tan(theta) @property
span = radius * t def _theta(self):
radius_proj = radius / c return math.pi / self.n_tooth
span_inner = radius_inner * s
# 2 * raise + (inner tooth height) = (tooth height)
inner_raise = (tooth_height - tooth_height_inner) / 2
# Outer tooth triangle spans 2*theta radians. This profile is the radial
# profile projected onto a plane `radius` away from the centre of the
# cylinder. The y coordinates on the edge must drop to compensate.
# The drop is equal to, via similar triangles @property
drop = inner_raise * (radius_proj - radius) / (radius - radius_inner) def tooth_angle(self):
outer = [ return hirth_tooth_angle(self.n_tooth)
(span, -tol - drop),
(span, -drop),
(0, tooth_height),
(-span, -drop),
(-span, -tol - drop),
]
adj = radius_inner * c
# In the case of the inner triangle, it is projected onto a plane `adj` away
# from the centre. The apex must extrapolate
# Via similar triangles
#
# (inner_raise + tooth_height_inner) -
# (tooth_height - inner_raise - tooth_height_inner) * ((radius_inner - adj) / (radius - radius_inner))
apex = (inner_raise + tooth_height_inner) - \
inner_raise * (radius_inner - adj) / (radius - radius_inner)
inner = [
(span_inner, -tol),
(span_inner, inner_raise),
(0, apex),
(-span_inner, inner_raise),
(-span_inner, -tol),
]
tooth = (
Cq.Workplane('YZ')
.polyline(inner)
.close()
.workplane(offset=radius - adj)
.polyline(outer)
.close()
.loft(ruled=False, combine=True)
.val()
)
angle_offset = hirth_tooth_angle(n_tooth) / 2 if is_mated else 0
teeth = (
Cq.Workplane('XY')
.polarArray(
radius=adj,
startAngle=angle_offset,
angle=360,
count=n_tooth)
.eachpoint(lambda loc: tooth.located(loc))
.intersect(Cq.Solid.makeCylinder(
height=base_height + tooth_height,
radius=radius,
))
.intersect(Cq.Solid.makeCylinder(
height=base_height + tooth_height,
radius=radius,
))
.cut(Cq.Solid.makeCylinder(
height=base_height + tooth_height,
radius=radius_inner,
))
)
base = (
Cq.Workplane('XY')
.cylinder(
height=base_height,
radius=radius,
centered=(True, True, False))
.faces(">Z").tag(f"{tag_prefix}bore")
.union(teeth.val().move(Cq.Location((0,0,base_height))), tol=tol)
.clean()
)
#base.workplane(offset=tooth_height/2).circle(radius=radius,forConstruction=True).tag("mate")
(
base
.polyline([(0, 0, base_height), (0, 0, base_height+tooth_height)], forConstruction=True)
.tag(f"{tag_prefix}mate")
)
(
base
.polyline([(0, 0, 0), (1, 0, 0)], forConstruction=True)
.tag(f"{tag_prefix}directrix")
)
return base
def hirth_assembly(n_tooth=12): def generate(self, tag_prefix="", is_mated=False, tol=0.01):
""" """
Example assembly of two Hirth joints is_mated: If set to true, rotate the teeth so they line up at 0 degrees.
"""
#rotate = 180 / 16
tab = ( FIXME: The curves don't mate perfectly. See if non-planar lofts can solve
Cq.Workplane('XY') this issue.
.box(100, 10, 2, centered=False) """
) c, s, t = math.cos(self._theta), math.sin(self._theta), math.tan(self._theta)
obj1 = ( span = self.radius * t
hirth_joint(n_tooth=n_tooth) radius_proj = self.radius / c
.faces(tag="bore") span_inner = self.radius_inner * s
.cboreHole( # 2 * raise + (inner tooth height) = (tooth height)
diameter=10, inner_raise = (self.tooth_height - self.tooth_height_inner) / 2
cboreDiameter=20, # Outer tooth triangle spans 2*theta radians. This profile is the radial
cboreDepth=3) # profile projected onto a plane `radius` away from the centre of the
.union(tab) # cylinder. The y coordinates on the edge must drop to compensate.
)
obj2 = ( # The drop is equal to, via similar triangles
hirth_joint(n_tooth=n_tooth, is_mated=True) drop = inner_raise * (radius_proj - self.radius) / (self.radius - self.radius_inner)
.union(tab) outer = [
) (span, -tol - drop),
angle = hirth_tooth_angle(n_tooth) (span, -drop),
result = ( (0, self.tooth_height),
Cq.Assembly() (-span, -drop),
.add(obj1, name="obj1", color=Role.PARENT.color) (-span, -tol - drop),
.add(obj2, name="obj2", color=Role.CHILD.color) ]
.constrain("obj1", "Fixed") adj = self.radius_inner * c
.constrain("obj1?mate", "obj2?mate", "Plane") # In the case of the inner triangle, it is projected onto a plane `adj` away
.constrain("obj1?directrix", "obj2?directrix", "Axis", param=angle) # from the centre. The apex must extrapolate
.solve()
) # Via similar triangles
return result #
# (inner_raise + tooth_height_inner) -
# (tooth_height - inner_raise - tooth_height_inner) * ((radius_inner - adj) / (radius - radius_inner))
apex = (inner_raise + self.tooth_height_inner) - \
inner_raise * (self.radius_inner - adj) / (self.radius - self.radius_inner)
inner = [
(span_inner, -tol),
(span_inner, inner_raise),
(0, apex),
(-span_inner, inner_raise),
(-span_inner, -tol),
]
tooth = (
Cq.Workplane('YZ')
.polyline(inner)
.close()
.workplane(offset=self.radius - adj)
.polyline(outer)
.close()
.loft(ruled=False, combine=True)
.val()
)
angle_offset = hirth_tooth_angle(self.n_tooth) / 2 if is_mated else 0
h = self.base_height + self.tooth_height
teeth = (
Cq.Workplane('XY')
.polarArray(
radius=adj,
startAngle=angle_offset,
angle=360,
count=self.n_tooth)
.eachpoint(lambda loc: tooth.located(loc))
.intersect(Cq.Solid.makeCylinder(
height=h,
radius=self.radius,
))
.cut(Cq.Solid.makeCylinder(
height=h,
radius=self.radius_inner,
))
)
base = (
Cq.Workplane('XY')
.cylinder(
height=self.base_height,
radius=self.radius,
centered=(True, True, False))
.faces(">Z").tag(f"{tag_prefix}bore")
.union(
teeth.val().move(Cq.Location((0,0,self.base_height))),
tol=tol)
.clean()
)
#base.workplane(offset=tooth_height/2).circle(radius=radius,forConstruction=True).tag("mate")
(
base
.polyline([
(0, 0, self.base_height),
(0, 0, self.base_height + self.tooth_height)
], forConstruction=True)
.tag(f"{tag_prefix}mate")
)
(
base
.polyline([(0, 0, 0), (1, 0, 0)], forConstruction=True)
.tag(f"{tag_prefix}directrix")
)
return base
def assembly(self):
"""
Generate an example assembly
"""
tab = (
Cq.Workplane('XY')
.box(100, 10, 2, centered=False)
)
obj1 = (
self.generate()
.faces(tag="bore")
.cboreHole(
diameter=10,
cboreDiameter=20,
cboreDepth=3)
.union(tab)
)
obj2 = (
self.generate(is_mated=True)
.union(tab)
)
angle = 1 * self.tooth_angle
result = (
Cq.Assembly()
.add(obj1, name="obj1", color=Role.PARENT.color)
.add(obj2, name="obj2", color=Role.CHILD.color)
.constrain("obj1", "Fixed")
.constrain("obj1?mate", "obj2?mate", "Plane")
.constrain("obj1?directrix", "obj2?directrix", "Axis", param=angle)
.solve()
)
return result
def comma_joint(radius=30, def comma_joint(radius=30,
shaft_radius=10, shaft_radius=10,
@ -429,10 +438,10 @@ class TorsionJoint:
spring = self.spring() spring = self.spring()
result = ( result = (
Cq.Assembly() Cq.Assembly()
.add(spring, name="spring", color=Cq.Color(0.5,0.5,0.5,1)) .add(spring, name="spring", color=Role.DAMPING.color)
.add(track, name="track", color=Cq.Color(0.5,0.5,0.8,0.3)) .add(track, name="track", color=Role.PARENT.color)
.constrain("track?spring", "spring?top", "Plane") .constrain("track?spring", "spring?top", "Plane")
.add(rider, name="rider", color=Cq.Color(0.8,0.8,0.5,0.3)) .add(rider, name="rider", color=Role.CHILD.color)
.constrain("rider?spring", "spring?bot", "Plane") .constrain("rider?spring", "spring?bot", "Plane")
.constrain("track?directrix", "spring?directrix_bot", "Axis") .constrain("track?directrix", "spring?directrix_bot", "Axis")
.constrain("rider?directrix0", "spring?directrix_top", "Axis") .constrain("rider?directrix0", "spring?directrix_top", "Axis")

View File

@ -16,6 +16,7 @@ class Role(Enum):
# Parent and child components in a load bearing joint # Parent and child components in a load bearing joint
PARENT = _color('blue4', 0.6) PARENT = _color('blue4', 0.6)
CHILD = _color('darkorange2', 0.6) CHILD = _color('darkorange2', 0.6)
DAMPING = _color('springgreen', 0.5)
STRUCTURE = _color('gray', 0.4) STRUCTURE = _color('gray', 0.4)
DECORATION = _color('lightseagreen', 0.4) DECORATION = _color('lightseagreen', 0.4)
ELECTRONIC = _color('mediumorchid', 0.5) ELECTRONIC = _color('mediumorchid', 0.5)

View File

@ -8,12 +8,14 @@ from nhf.checks import binary_intersection
class TestJoints(unittest.TestCase): class TestJoints(unittest.TestCase):
def test_joint_hirth(self): def test_joint_hirth(self):
j = nhf.joints.hirth_joint() j = nhf.joints.HirthJoint()
obj = j.generate()
self.assertIsInstance( self.assertIsInstance(
j.val().solids(), Cq.Solid, obj.val().solids(), Cq.Solid,
msg="Hirth joint must be in one piece") msg="Hirth joint must be in one piece")
def test_joints_hirth_assembly(self): def test_joints_hirth_assembly(self):
assembly = nhf.joints.hirth_assembly() j = nhf.joints.HirthJoint()
assembly = j.assembly()
isect = binary_intersection(assembly) isect = binary_intersection(assembly)
self.assertLess(isect.Volume(), 1e-6, self.assertLess(isect.Volume(), 1e-6,
"Hirth joint assembly must not have intersection") "Hirth joint assembly must not have intersection")

View File

@ -30,10 +30,12 @@ import cadquery as Cq
import nhf.joints import nhf.joints
import nhf.handle import nhf.handle
from nhf import Material from nhf import Material
from nhf.joints import HirthJoint
from nhf.handle import Handle
import nhf.touhou.houjuu_nue.wing as MW import nhf.touhou.houjuu_nue.wing as MW
import nhf.touhou.houjuu_nue.trident as MT import nhf.touhou.houjuu_nue.trident as MT
@dataclass(frozen=True) @dataclass
class Parameters: class Parameters:
""" """
Defines dimensions for the Houjuu Nue cosplay Defines dimensions for the Houjuu Nue cosplay
@ -44,9 +46,9 @@ class Parameters:
# Harness # Harness
harness_thickness: float = 25.4 / 8 harness_thickness: float = 25.4 / 8
harness_width = 300 harness_width: float = 300
harness_height = 400 harness_height: float = 400
harness_fillet = 10 harness_fillet: float = 10
harness_wing_base_pos = [ harness_wing_base_pos = [
("r1", 70, 150), ("r1", 70, 150),
@ -60,36 +62,39 @@ class Parameters:
# Holes drilled onto harness for attachment with HS joint # Holes drilled onto harness for attachment with HS joint
harness_to_root_conn_diam = 6 harness_to_root_conn_diam = 6
hs_hirth_joint: HirthJoint = HirthJoint(
radius=30,
radius_inner=20,
tooth_height=10,
base_height=5
)
# Wing root properties # Wing root properties
# #
# The Houjuu-Scarlett joint mechanism at the base of the wing # The Houjuu-Scarlett joint mechanism at the base of the wing
hs_joint_base_width = 85 hs_joint_base_width: float = 85
hs_joint_base_thickness = 10 hs_joint_base_thickness: float = 10
hs_joint_ring_thickness = 5 hs_joint_corner_fillet: float = 5
hs_joint_tooth_height = 10 hs_joint_corner_cbore_diam: float = 12
hs_joint_radius = 30 hs_joint_corner_cbore_depth: float = 2
hs_joint_radius_inner = 20 hs_joint_corner_inset: float = 12
hs_joint_corner_fillet = 5
hs_joint_corner_cbore_diam = 12
hs_joint_corner_cbore_depth = 2
hs_joint_corner_inset = 12
hs_joint_axis_diam = 12 hs_joint_axis_diam: float = 12
hs_joint_axis_cbore_diam = 20 hs_joint_axis_cbore_diam: float = 20
hs_joint_axis_cbore_depth = 3 hs_joint_axis_cbore_depth: float = 3
# Exterior radius of the wing root assembly # Exterior radius of the wing root assembly
wing_root_radius = 40 wing_root_radius: float = 40
""" """
Heights for various wing joints, where the numbers start from the first joint. Heights for various wing joints, where the numbers start from the first joint.
""" """
wing_r1_height = 100 wing_r1_height: float = 100
wing_r1_width = 400 wing_r1_width: float = 400
wing_r2_height = 100 wing_r2_height: float = 100
wing_r3_height = 100 wing_r3_height: float = 100
trident_handle: nhf.handle.Handle = nhf.handle.Handle( trident_handle: Handle = Handle(
diam=38, diam=38,
diam_inner=33, diam_inner=33,
# M27-3 # M27-3
@ -100,7 +105,7 @@ class Parameters:
) )
def __post_init__(self): def __post_init__(self):
assert self.wing_root_radius > self.hs_joint_radius,\ assert self.wing_root_radius > self.hs_hirth_joint.radius,\
"Wing root must be large enough to accomodate joint" "Wing root must be large enough to accomodate joint"
@ -174,20 +179,12 @@ class Parameters:
(-dx, dx), (-dx, dx),
] ]
def hs_joint_component(self):
hirth = nhf.joints.hirth_joint(
radius=self.hs_joint_radius,
radius_inner=self.hs_joint_radius_inner,
tooth_height=self.hs_joint_tooth_height,
base_height=self.hs_joint_ring_thickness)
return hirth
def hs_joint_parent(self): def hs_joint_parent(self):
""" """
Parent part of the Houjuu-Scarlett joint, which is composed of a Hirth Parent part of the Houjuu-Scarlett joint, which is composed of a Hirth
coupling, a cylindrical base, and a mounting base. coupling, a cylindrical base, and a mounting base.
""" """
hirth = self.hs_joint_component().val() hirth = self.hs_hirth_joint.generate()
#hirth = ( #hirth = (
# hirth # hirth
# .faces("<Z") # .faces("<Z")
@ -231,7 +228,7 @@ class Parameters:
result result
.faces(">Z") .faces(">Z")
.workplane() .workplane()
.union(hirth.move(Cq.Location((0, 0, self.hs_joint_base_thickness))), tol=0.1) .union(hirth.translate((0, 0, self.hs_joint_base_thickness)), tol=0.1)
.clean() .clean()
) )
result = ( result = (
@ -247,7 +244,12 @@ class Parameters:
result.faces("<Z").tag("base") result.faces("<Z").tag("base")
return result return result
def wing_root(self) -> Cq.Shape:
"""
Generate the wing root which contains a Hirth joint at its base and a
rectangular opening on its side, with the necessary interfaces.
"""
return MW.wing_root(joint=self.hs_hirth_joint)
def wing_r1_profile(self) -> Cq.Sketch: def wing_r1_profile(self) -> Cq.Sketch:
""" """
@ -288,13 +290,6 @@ class Parameters:
) )
return result return result
def wing_root(self) -> Cq.Shape:
"""
Generate the wing root which contains a Hirth joint at its base and a
rectangular opening on its side, with the necessary interfaces.
"""
return MW.wing_root()
###################### ######################
# Assemblies # # Assemblies #
###################### ######################
@ -310,12 +305,18 @@ class Parameters:
j = self.hs_joint_parent() j = self.hs_joint_parent()
( (
result result
.add(j, name=f"hs_{name}p", color=Material.PLASTIC_PLA.color) .add(j, name=f"hs_{name}", color=Material.PLASTIC_PLA.color)
#.constrain(f"harness?{name}", f"hs_{name}p?mate", "Point") #.constrain(f"harness?{name}", f"hs_{name}p?mate", "Point")
.constrain("harness?mount", f"hs_{name}p?base", "Axis") .constrain("harness?mount", f"hs_{name}?base", "Axis")
) )
for i in range(4): for i in range(4):
result.constrain(f"harness?{name}_{i}", f"hs_{name}p?h{i}", "Point") result.constrain(f"harness?{name}_{i}", f"hs_{name}?h{i}", "Point")
angle = 6 * self.hs_hirth_joint.tooth_angle
(
result.add(self.wing_root(), name="w0_r1", color=Material.PLASTIC_PLA.color)
.constrain("w0_r1?mate", "hs_r1?mate", "Plane")
.constrain("w0_r1?directrix", "hs_r1?directrix", "Axis", param=angle)
)
result.solve() result.solve()
return result return result

View File

@ -20,7 +20,7 @@ class Test(unittest.TestCase):
self.assertLess(bbox.zlen, 255, msg=msg) self.assertLess(bbox.zlen, 255, msg=msg)
def test_wings(self): def test_wings(self):
p = M.Parameters() p = M.Parameters()
p.wing_r1() p.wing_root()
def test_harness(self): def test_harness(self):
p = M.Parameters() p = M.Parameters()
p.harness_assembly() p.harness_assembly()

View File

@ -1,5 +1,10 @@
"""
This file describes the shapes of the wing shells. The joints are defined in
`__init__.py`.
"""
import math import math
import cadquery as Cq import cadquery as Cq
from nhf.joints import HirthJoint
def wing_root_profiles( def wing_root_profiles(
base_sweep=150, base_sweep=150,
@ -117,7 +122,13 @@ def wing_root_profiles(
.wires().val() .wires().val()
) )
return base, middle, tip return base, middle, tip
def wing_root():
def wing_root(joint: HirthJoint,
bolt_diam: int = 12):
"""
Generate the contiguous components of the root wing segment
"""
root_profile, middle_profile, tip_profile = wing_root_profiles() root_profile, middle_profile, tip_profile = wing_root_profiles()
rotate_centre = Cq.Vector(-200, 0, -25) rotate_centre = Cq.Vector(-200, 0, -25)
@ -175,4 +186,16 @@ def wing_root():
result = seg1.union(seg2).union(seg3) result = seg1.union(seg2).union(seg3)
result.faces("<Z").tag("base") result.faces("<Z").tag("base")
result.faces(">X").tag("conn") result.faces(">X").tag("conn")
j = (
joint.generate(is_mated=True)
.faces("<Z")
.hole(bolt_diam)
)
result = (
result
.union(j.translate((0, 0, -10)))
.union(Cq.Solid.makeCylinder(57, 5).moved(Cq.Location((0, 0, -10))))
.clean()
)
return result return result