Commit acc9f351 authored by Jan Koniarik's avatar Jan Koniarik
Browse files

wololo

parent 7b25a32f
*.pyc
.pycad/
schpin_koke/src/scad/gen/
schpin_koke/dist/
schpin_robot_lib/dist/
schpin_koke/.cabal-sandbox/
*.stl
*.stlb
*.swp
*.swo
all: src/stl/body/body.stl src/stl/body/body_collision_a.stl src/stl/leg/rr/coxa/coxa.stl src/stl/leg/rr/coxa/coxa_collision.stl src/stl/leg/rr/femur/femur.stl src/stl/leg/rr/femur/femur_collision_a.stl src/stl/leg/rr/femur/femur_collision_b.stl src/stl/leg/rr/tibia/tibia.stl src/stl/leg/rr/tibia/tibia_collision.stl src/stl/leg/rl/coxa/coxa.stl src/stl/leg/rl/coxa/coxa_collision.stl src/stl/leg/rl/femur/femur.stl src/stl/leg/rl/femur/femur_collision_a.stl src/stl/leg/rl/femur/femur_collision_b.stl src/stl/leg/rl/tibia/tibia.stl src/stl/leg/rl/tibia/tibia_collision.stl src/stl/leg/fr/coxa/coxa.stl src/stl/leg/fr/coxa/coxa_collision.stl src/stl/leg/fr/femur/femur.stl src/stl/leg/fr/femur/femur_collision_a.stl src/stl/leg/fr/femur/femur_collision_b.stl src/stl/leg/fr/tibia/tibia.stl src/stl/leg/fr/tibia/tibia_collision.stl src/stl/leg/fl/coxa/coxa.stl src/stl/leg/fl/coxa/coxa_collision.stl src/stl/leg/fl/femur/femur.stl src/stl/leg/fl/femur/femur_collision_a.stl src/stl/leg/fl/femur/femur_collision_b.stl src/stl/leg/fl/tibia/tibia.stl src/stl/leg/fl/tibia/tibia_collision.stl
all: src/stl/body/body.stl src/stl/body/body_collision.stl src/stl/leg/rr/coxa/coxa.stl src/stl/leg/rr/coxa/coxa_collision.stl src/stl/leg/rr/femur/femur.stl src/stl/leg/rr/femur/femur_collision_a.stl src/stl/leg/rr/femur/femur_collision_b.stl src/stl/leg/rr/tibia/tibia.stl src/stl/leg/rr/tibia/tibia_collision.stl src/stl/leg/rl/coxa/coxa.stl src/stl/leg/rl/coxa/coxa_collision.stl src/stl/leg/rl/femur/femur.stl src/stl/leg/rl/femur/femur_collision_a.stl src/stl/leg/rl/femur/femur_collision_b.stl src/stl/leg/rl/tibia/tibia.stl src/stl/leg/rl/tibia/tibia_collision.stl src/stl/leg/fr/coxa/coxa.stl src/stl/leg/fr/coxa/coxa_collision.stl src/stl/leg/fr/femur/femur.stl src/stl/leg/fr/femur/femur_collision_a.stl src/stl/leg/fr/femur/femur_collision_b.stl src/stl/leg/fr/tibia/tibia.stl src/stl/leg/fr/tibia/tibia_collision.stl src/stl/leg/fl/coxa/coxa.stl src/stl/leg/fl/coxa/coxa_collision.stl src/stl/leg/fl/femur/femur.stl src/stl/leg/fl/femur/femur_collision_a.stl src/stl/leg/fl/femur/femur_collision_b.stl src/stl/leg/fl/tibia/tibia.stl src/stl/leg/fl/tibia/tibia_collision.stl
src/stl/body/body.stl: src/scad/gen/body/body.scad
mkdir -p `dirname src/stl/body/body.stl`
openscad -o src/stl/body/body.stl src/scad/gen/body/body.scad
admesh --write-binary-stl=src/stl/body/body.stl --no-check src/stl/body/body.stl
src/stl/body/body_collision_a.stl: src/scad/gen/body/body_collision_a.scad
mkdir -p `dirname src/stl/body/body_collision_a.stl`
openscad -o src/stl/body/body_collision_a.stl src/scad/gen/body/body_collision_a.scad
admesh --write-binary-stl=src/stl/body/body_collision_a.stl --no-check src/stl/body/body_collision_a.stl
src/stl/body/body_collision.stl: src/scad/gen/body/body_collision.scad
mkdir -p `dirname src/stl/body/body_collision.stl`
openscad -o src/stl/body/body_collision.stl src/scad/gen/body/body_collision.scad
admesh --write-binary-stl=src/stl/body/body_collision.stl --no-check src/stl/body/body_collision.stl
src/stl/leg/rr/coxa/coxa.stl: src/scad/gen/leg/rr/coxa/coxa.scad
mkdir -p `dirname src/stl/leg/rr/coxa/coxa.stl`
openscad -o src/stl/leg/rr/coxa/coxa.stl src/scad/gen/leg/rr/coxa/coxa.scad
......
#!/usr/bin/env runhaskell
import Data.SCAD
import Data.Shared
......@@ -7,153 +7,197 @@ import Data.URDF.Xml (writeXML)
import Data.Walker
import Linear.Quaternion
import Linear.V3
import Numeric.Units.Dimensional.Prelude ((*~), degree, radian, second)
import Numeric.Units.Dimensional.Prelude (degree, radian, second,
(*~))
import qualified Numeric.Units.Dimensional.Prelude as D
data LegPos = RL | RR | FR | FL deriving Eq;
kokeTipPos = V3 (90 *~ mm) (0 *~ mm) (0 *~ mm)
femurOffset :: Pose
femurOffset = Pose (V3 (61.3 *~ mm) (0 *~ mm) (0 *~ mm)) $ toQuat zAxis (0 *~ degree)
data ConfType = Default | Folded | Expanded deriving (Show, Eq);
kokeTipPos = V3 (100 *~ mm) (0 *~ mm) (0 *~ mm)
femurOffset :: ConfType -> Pose
femurOffset conf_type =
Pose
( V3 (if conf_type == Expanded then 100 *~ mm else 60 *~ mm)
(0 *~ mm)
(0 *~ mm)
)
$ toQuat zAxis (0 *~ degree)
tibiaOffset :: Pose
tibiaOffset = Pose (V3 (86 *~ mm) (0 *~ mm) (0 *~ mm)) $ toQuat yAxis (90 *~ degree)
legPose :: LegPos -> Pose
legPose pos = Pose (V3 x y (0 *~ mm)) $ toQuat zAxis ( angle *~ degree )
where
x = case pos of
FR -> 36 *~ mm
RR -> 36 *~ mm
FL -> (-36) *~ mm
RL -> (-36) *~ mm
y = case pos of
FL -> 45 *~ mm
FR -> 45 *~ mm
RR -> (-45) *~ mm
RL -> (-45) *~ mm
angle = standingZAngles pos
standingZAngles :: LegPos -> Double
standingZAngles pos = case pos of
RL -> -90 - 45
RR -> -90 + 45
FL -> 90 + 45
FR -> 90 - 45
foldedZAngles :: LegPos -> Double
foldedZAngles pos = case pos of
RL -> -90
RR -> -90
FL -> 90
FR -> 90
tibia = Part {
model = scadModel "tibia" [ ("tipOffset",kokeTipPos) ] ["tibia.scad"],
collision_models = [
scadModel "tibia_collision" [("tipOffset", kokeTipPos)] ["tibia.scad"]
],
part_weight = Nothing,
center_of_mass = Nothing
}
femur = Part {
model = scadModel "femur" [ ( "tibiaOffset", pos $ tibiaOffset)] ["femur.scad"],
collision_models = [
scadModel "femur_collision_a" [("tibiaOffset", pos $ tibiaOffset)] ["femur.scad"],
scadModel "femur_collision_b" [("tibiaOffset", pos $ tibiaOffset)] ["femur.scad"]
],
part_weight = Nothing,
center_of_mass = Nothing
}
coxa = Part {
model = scadModel "coxa" [ ( "femurOffset", pos $ femurOffset)] ["coxa.scad"],
collision_models = [
scadModel "coxa_collision" [ ( "femurOffset", pos $ femurOffset)] ["coxa.scad"]
],
part_weight = Nothing,
center_of_mass = Nothing
}
kokeBody legs = Body $ Part {
model = scadModel "body" [("positions", map leg_pose legs)] ["body.scad"],
collision_models = [
scadModel "body_collision_a" [("positions", map leg_pose legs)] ["body.scad"]
],
part_weight = Nothing,
center_of_mass = Nothing
}
where
leg_pose leg = pos $ offset $ head $ chain leg
leg :: LegPos -> Leg
leg pos = Leg {
leg_name = case pos of
RL -> "rl"
RR -> "rr"
FL -> "fl"
FR -> "fr"
,
chain = [
Link { link_name = "coxa",
offset= legPose pos,
part = coxa,
axis = zAxis,
joint_config = JointConfig{
min_angle = (-3*pi/8) *~ radian,
default_angle = 0 *~ radian,
max_angle = (3*pi/8) *~ radian,
vel_lim = 50 *~ (radian D./ second),
effor_lim = 100,
g_steps = 8
}},
Link { link_name = "femur",
offset = femurOffset,
part = femur,
axis = yAxis,
joint_config = JointConfig {
min_angle=(-3*pi/8) *~ radian,
default_angle=(-pi/8) *~ radian,
max_angle=(3*pi/8) *~ radian,
vel_lim= 50 *~ (radian D./ second),
effor_lim = 100,
g_steps= 8
}},
Link {
link_name ="tibia",
offset = tibiaOffset,
part = tibia,
axis = yAxis,
joint_config = JointConfig {
min_angle = (-3*pi/8) *~ radian,
default_angle = (pi/8) *~ radian,
max_angle = (3*pi/8) *~ radian,
vel_lim = 50 *~ (radian D./ second),
effor_lim = 100,
g_steps = 8
}
}
],
tip = Tip {
point = kokeTipPos
},
pose = noOffset -- is not considered during offset in schpin_ompl -> remove
}
koke :: Walker
koke = Walker walker_name legs (kokeBody legs)
where
walker_name = "Tote"
legs = [leg RR, leg RL, leg FR, leg FL]
tibiaOffset =
Pose (V3 (95 *~ mm) (0 *~ mm) (30 *~ mm)) $ toQuat yAxis (90 *~ degree)
legPose :: LegPos -> ConfType -> Pose
legPose pos conf_type = Pose (V3 x y (0 *~ mm))
$ toQuat zAxis (angle *~ degree)
where
x_val = if conf_type == Expanded then 85 else 45
x = case pos of
FR -> (x_val) *~ mm
FL -> (x_val) *~ mm
RR -> (-x_val) *~ mm
RL -> (-x_val) *~ mm
y_val = 36
y = case pos of
FR -> (y_val) *~ mm
FL -> (-y_val) *~ mm
RR -> (y_val) *~ mm
RL -> (-y_val) *~ mm
angle = case pos of
FR -> 90 - 45
FL -> -90 + 45
RR -> 90 + 45
RL -> -90 - 45
leg :: LegPos -> ConfType -> Leg
leg leg_pos conf_type = Leg
{ leg_name = case leg_pos of
RL -> "rl"
RR -> "rr"
FL -> "fl"
FR -> "fr"
, chain = [ Link
{ link_name = "coxa"
, offset = legPose leg_pos conf_type
, part = Part
{ model = SCADModel
"coxa"
[ toArg "femurOffset" $ pos $ femurOffset Default
, toArg
"expand"
(if conf_type == Expanded then 10 *~ mm else 0 *~ mm)
]
["coxa.scad"]
, collision_models = [ SCADModel
"coxa_collision"
[ toArg "femurOffset"
$ pos
$ femurOffset Default
]
["coxa.scad"]
]
, part_weight = Nothing
, center_of_mass = Nothing
}
, axis = zAxis
, joint_config = JointConfig
{ min_angle = (-3 * pi / 8) *~ radian
, default_angle = if conf_type == Folded
then case leg_pos of
FR -> (-45) *~ degree
FL -> 45 *~ degree
RR -> 45 *~ degree
RL -> (-45) *~ degree
else 0 *~ radian
, max_angle = (3 * pi / 8) *~ radian
, vel_lim = 50 *~ (radian D./ second)
, effor_lim = 100
, g_steps = 8
}
}
, Link
{ link_name = "femur"
, offset = femurOffset conf_type
, part = Part
{ model = SCADModel
"femur"
[ toArg "tibiaOffset" $ pos $ tibiaOffset
, toArg
"expand"
(if conf_type == Expanded then 10 *~ mm else 0 *~ mm)
]
["femur.scad"]
, collision_models = [ SCADModel
"femur_collision_a"
[toArg "tibiaOffset" $ pos $ tibiaOffset]
["femur.scad"]
, SCADModel
"femur_collision_b"
[toArg "tibiaOffset" $ pos $ tibiaOffset]
["femur.scad"]
]
, part_weight = Nothing
, center_of_mass = Nothing
}
, axis = yAxis
, joint_config = JointConfig
{ min_angle = (-3 * pi / 8) *~ radian
, default_angle = if conf_type == Folded
then (pi * 0.95) *~ radian
else (-pi / 12) *~ radian
, max_angle = (3 * pi / 8) *~ radian
, vel_lim = 50 *~ (radian D./ second)
, effor_lim = 100
, g_steps = 8
}
}
, Link
{ link_name = "tibia"
, offset = tibiaOffset
, part = Part
{ model = SCADModel
"tibia"
[ toArg "tipOffset" kokeTipPos
, toArg
"expand"
(if conf_type == Expanded then 10 *~ mm else 0 *~ mm)
]
["tibia.scad"]
, collision_models = [ SCADModel
"tibia_collision"
[toArg "tipOffset" kokeTipPos]
["tibia.scad"]
]
, part_weight = Nothing
, center_of_mass = Nothing
}
, axis = yAxis
, joint_config = JointConfig
{ min_angle = (-3 * pi / 8) *~ radian
, default_angle = if conf_type == Folded
then (-pi * 1.45) *~ radian
else (-pi / 12) *~ radian
, max_angle = (3 * pi / 8) *~ radian
, vel_lim = 50 *~ (radian D./ second)
, effor_lim = 100
, g_steps = 8
}
}
]
, tip = Tip {point = kokeTipPos}
, pose = noOffset -- is not considered during offset in schpin_ompl -> remove
}
koke :: ConfType -> Walker
koke conf_type = Walker walker_name legs $ Body Part
{ model = SCADModel
"body"
[ toArg "positions" leg_positions
, toArg "expand" (if conf_type == Expanded then 10 *~ mm else 0 *~ mm)
]
["body.scad"]
, collision_models = [ SCADModel "body_collision"
[toArg "positions" leg_positions]
["body.scad"]
]
, part_weight = Nothing
, center_of_mass = Nothing
}
where
leg_positions = map (\x -> pos $ legPose x Default) [RR, RL, FR, FL]
walker_name = "Tote"
legs =
[leg RR conf_type, leg RL conf_type, leg FR conf_type, leg FL conf_type]
main :: IO ()
main = do
mapM_ (uncurry renderSCAD) $ getSCAD koke
writeXML (getURDF koke) "src/urdf/koke.urdf"
writeSRDFXML (getSRDF koke) "src/srdf/koke.srdf"
renderWalkerStl koke
mapM_ (uncurry renderSCAD) $ getSCADFiles (koke Default)
mapM_ (uncurry renderSCAD) $ getSCADSkeletons "default" (koke Default)
mapM_ (uncurry renderSCAD) $ getSCADSkeletons "folded" (koke Folded)
mapM_ (uncurry renderSCAD) $ getSCADSkeletons "expanded" (koke Expanded)
writeXML (getURDF (koke Default)) "src/urdf/koke.urdf"
writeSRDFXML (getSRDF (koke Default)) "src/srdf/koke.srdf"
renderWalkerStl (koke Default)
include<metric.scad>;
include<tile.scad>;
include<util.scad>;
LX15D_dim = [ 44.17, 22.95, 26 ];
LX15D_dim = [ 44.17, 22.95, 25.5 ];
LX15D_middle_t = 1.5; // height of the middle space
LX15D_middle_a = 3.0; // side space
LX15D_axis_offset = 10.66;
......@@ -14,21 +16,33 @@ LX15D_body_screw_d = 2;
LX15D_horn_clearance_d = 8;
LX15D_clearance_r = sqrt(pow(LX15D_dim[1] / 2, 2) + pow(LX15D_axis_offset, 2));
module LX15D() color("gray") {
module LX15D() finalize("gray") difference() {
dim = LX15D_dim;
translate([ dim[0] / 2 - LX15D_axis_offset, 0, 0 ]) {
cube(dim, center = true);
difference() {
cube(dim + [ -LX15D_middle_a, -LX15D_middle_a, LX15D_middle_t * 2 ],
center = true);
for (i = [ -0.5, 0.5 ], j = [ -0.5, 0.5 ])
translate([ dim[0] * i, dim[1] * j, 0 ])
cylinder(d = 13, h = 100, center = true);
union() {
translate([ dim[0] / 2 - LX15D_axis_offset, 0, 0 ]) {
cube(dim, center = true);
difference() {
cube(
dim +
[
-LX15D_middle_a, -LX15D_middle_a, LX15D_middle_t * 2
],
center = true);
for (i = [ -0.5, 0.5 ], j = [ -0.5, 0.5 ])
translate([ dim[0] * i, dim[1] * j, 0 ])
cylinder(d = 13, h = 100, center = true);
}
}
}
cylinder(d = LX15D_horn_d, h = LX15D_horn_w, center = true);
cylinder(d = LX15D_horn_d, h = LX15D_horn_w, center = true);
}
for (i = [ -1, 1 ]) {
LX15D_horn_screw_pos() translate([ 0, 0, i * LX15D_horn_w / 2 ])
cylinder(d = LX15D_horn_screw_d, h = 10, center = true);
}
for (m = [ 0, 1 ])
mirror([ 0, 0, m ]) LX15D_bottom_screw_pos()
cylinder(d = LX15D_body_screw_d, h = 4, center = true);
}
module LX15D_collision() {
......@@ -77,63 +91,143 @@ module LX15D_side_plate(screw_d, holes, t) difference() {
}
LX15D_U_h = 6;
LX15D_U_c = 0.2;
LX15D_U_offset =
[ LX15D_dim[0] - LX15D_axis_offset + LX15D_U_c + LX15D_U_h, 0, 0 ];
module LX15D_U() render() difference() {
a = 24;
LX15D_U_offset = [ 40, 0, 0 ];
LX15D_U_screw_y = 16;
module LX15D_U_body(class) difference() {
t = 2;
union() {
translate([ LX15D_dim[0] - LX15D_axis_offset + LX15D_U_c, 0, 0 ])
difference() {
translate([ LX15D_U_h / 2, 0, 0 ])
cube([ LX15D_U_h, a, LX15D_dim[2] + t * 2 ], center = true);
translate([ LX15D_U_h, 0, 0 ]) rotate([ 0, -90, 0 ])
tile_neg(T24, LX15D_U_h);
}
translate([ -LX15D_U_h / 2, 0, 0 ])
cube([ LX15D_U_h, Ta(T24), LX15D_dim[2] ], center = true);
rotate([ 0, -90, 0 ]) tile_neg(T24, LX15D_U_h, centered_hole = true);
rotate([ 0, 90, 0 ])
cylinder(d = Ta(T24) / 2, h = 100, center = true, $fn = 8);
for (m = [ 0, 1 ])
mirror([ 0, 0, m ]) LX15D_bottom_screw_pos()
hull() for (x = [ 0, LX15D_U_h / 2 ]) translate([ x, 0, 0 ])
cylinder(d = LX15D_screw_clearance_d, h = t);
for (i = [ -0.5, 0.5 ], m = [ 0, 1 ])
mirror([ 0, 0, m ]) translate(
[ -LX15D_U_h / 2, i * LX15D_U_screw_y, -LX15D_dim[2] / 2 - t ]) {
Mscrew_hole(M2L8C);
translate([ 0, 0, 2 * t ]) Mnut_sidehole(M2N, l = 10);
}
}
module LX15D_U_plate(class) difference() {
t = 2;
union() {
translate(LX15D_U_offset -
[ LX15D_U_h / 2, 0, LX15D_dim[2] / 2 + t / 2 ])
cube([ LX15D_U_h, Ta(T24), t ], center = true);
mirror([ 0, 0, 1 ]) LX15D_bottom_screw_pos()
hull() for (x = [ 0, LX15D_U_h / 2 ]) translate([ x, 0, 0 ])
cylinder(d = LX15D_screw_clearance_d, h = t);
}
translate(LX15D_U_offset - [ LX15D_U_h / 2, 0, LX15D_dim[2] / 2 + t ]) {
for (i = [ -0.5, 0.5 ])
translate([ 0, i * LX15D_U_screw_y, 0 ]) Mscrew_hole(M2L8C);
}
LX15D_bottom_screw_pos()
cylinder(d = LX15D_body_screw_d, h = 100, center = true);
}
module LX15D_U(class, expand = 0) union() {
t = 2;
translate(LX15D_U_offset) finalize("blue") LX15D_U_body(class);
for (m = [ 0, 1 ]) mirror([ 0, 0, m ]) {
translate([ 0, 0, -expand ]) finalize("yellow")
LX15D_U_plate(class);
translate(LX15D_U_offset) for (i = [ -0.5, 0.5 ]) translate([
-LX15D_U_h / 2, i * LX15D_U_screw_y, -LX15D_dim[2] / 2 - t - 2 *
expand
]) Mscrew(M2L8C);
LX15D_bottom_screw_pos() translate([ 0, 0, 3 * expand + t ])
rotate([ 180, 0, 0 ]) Mscrew(M2L8C);
for (i = [ -0.5, 0.5 ])
translate(LX15D_U_offset + [
expand - LX15D_U_h / 2, i * LX15D_U_screw_y,
-LX15D_dim[2] / 2 +
t
]) Mnut(M2N);
}
}
LX15D_BU_h = 6;
LX15D_BU_screw_d = 3;
LX15D_BU_screw_h = 6;
LX15D_BU_t = 3;
LX15D_BU_screw_a = 10;
LX15D_BU_x_off = -LX15D_clearance_r - LX15D_BU_h / 2;
LX15D_BU_offset = [ -25, 0, 0 ];
module LX15D_BU_plate() difference() {
t = 3;
hull() translate([ 0, 0, LX15D_horn_w / 2 ]) {
LX15D_horn_screw_pos() cylinder(d = LX15D_horn_screw_d + t * 2, h = t);
t = LX15D_BU_t;
h = 5;
horn_a = LX15D_horn_screw_d + t;
bu_screw_a = Md(M2L8C) + t;
translate([ 0, 0, h / 2 ]) hull() {
LX15D_horn_screw_pos() cube([ horn_a, horn_a, h ], center = true);
for (i = [ -0.5, 0.5 ])
translate([ LX15D_BU_x_off, i * LX15D_BU_screw_a, 0 ])
cylinder(d = LX15D_BU_screw_d + t * 2, h = t);
translate(LX15D_BU_offset +
[ LX15D_BU_h / 2, i * LX15D_BU_screw_a, 0 ])
cube([ bu_screw_a, bu_screw_a, h ], center = true);
}
LX15D_horn_screw_pos()
cylinder(d = LX15D_horn_screw_d, h = 100, center = true);
cylinder(d = LX15D_horn_clearance_d, h = 100, center = true, $fn = 8);
LX15D_horn_screw_pos() Mscrew_hole(M3L8C);
for (i = [ -0.5, 0.5 ])
translate([ LX15D_BU_x_off, i * LX15D_BU_screw_a, 0 ])
cylinder(d = LX15D_BU_screw_d, h = 100, center = true);
translate(LX15D_BU_offset + [ LX15D_BU_h / 2, i * LX15D_BU_screw_a, t ])
rotate([ 180, 0, 0 ]) Mscrew_hole(M2L8C);
}
module LX15D_BU_body() difference() {
dim = [ LX15D_BU_h, LX15D_dim[1], LX15D_horn_w ];
x_off = LX15D_BU_x_off;
module LX15D_BU_body() translate(LX15D_BU_offset + [ LX15D_BU_h / 2, 0, 0 ])
difference() {
t = LX15D_BU_t;
dim = [ LX15D_BU_h, LX15D_BU_screw_a + t * 2, LX15D_horn_w ];
union() {
translate([ x_off, 0, 0 ]) difference() {
cube(dim, center = true);
rotate([ 0, 90, 0 ]) tile_neg(T24, LX15D_BU_h, center = true);
}
rotate([ 0, 90, 0 ]) tile_pos(T24, LX15D_BU_h, center = true);
cube(dim, center = true);
}
rotate([ 0, 90, 0 ])
tile_neg(T24, LX15D_BU_h, center = true);
for (j = [ -1, 1 ], i = [ -0.5, 0.5 ])
translate([ 0, i * LX15D_BU_screw_a, j * dim[2] / 2 ])
rotate([ j * 90 + 90, 0, 0 ]) {
Mscrew_hole(M2L8C);
translate([ 0, 0, t ]) Mnut_sidehole(M2N, l = 10);
}
}
module LX15D_BU(expand = 0) {
t = 3;
plate_h = 5;
finalize("yellow") LX15D_BU_body();
for (m = [ 0, 1 ])
mirror([ 0, 0, m ]) translate([ 0, 0, LX15D_horn_w / 2 + expand ]) {
finalize("blue") LX15D_BU_plate();
for (i = [ -0.5, 0.5 ])
translate(LX15D_BU_offset +
[ LX15D_BU_h / 2, i * LX15D_BU_screw_a, t + expand ])
rotate([ 180, 0, 0 ]) Mscrew(M2L8C);
for (z = [ -dim[2] / 2, dim[2] / 2 ], i = [ -0.5, 0.5 ])
translate([ x_off, i * LX15D_BU_screw_a, z ]) cylinder(
d = LX15D_BU_screw_d, h = LX15D_BU_screw_h * 2, center = true);
LX15D_horn_screw_pos() translate([ 0, 0, plate_h + expand ])
rotate([ 180, 0, 0 ]) Mscrew(M3L8C);
}
for (j = [ -1, 1 ], i = [ -0.5, 0.5 ])
translate(LX15D_BU_offset + [
LX15D_BU_h / 2 + expand, i * LX15D_BU_screw_a, j * LX15D_horn_w / 2
]) rotate([ j * 90 + 90, 0, 0 ]) {
translate([ 0, 0, t ]) Mnut(M2N, l = 10);
}
}
module LX15D_BU() {
render_part = "nothing";
if (render_part == "LX15D_BU_plate") {
$fn = 128;
LX15D_BU_plate();
} else if (render_part == "LX15D_BU_body") {
$fn = 128;
LX15D_BU_body();
for (m = [ 0, 1 ]) mirror([ 0, 0, m ]) LX15D_BU_plate();
} else if (render_part == "LX15D_U_plate") {
$fn = 128;
LX15D_U_plate();
} else if (render_part == "LX15D_U_body") {
$fn = 128;
LX15D_U_body();
}