Экспорт подсборок с мешами (SDF) и плана сборки (PDDL) из FreeCAD в виде архива zip
This commit is contained in:
parent
7f13c0056f
commit
e65236aab6
37 changed files with 1022 additions and 176 deletions
|
@ -13,7 +13,7 @@
|
|||
# License along with this library. If not, see <http://www.gnu.org/licenses/>.
|
||||
import FreeCAD
|
||||
import Tools
|
||||
from usecases.asm4parser_usecase import Asm4StructureParseUseCase
|
||||
from scenarios.robossembler_freecad_export_scenario import RobossemblerFreeCadExportScenario
|
||||
|
||||
if FreeCAD.GuiUp:
|
||||
import FreeCADGui
|
||||
|
@ -311,8 +311,9 @@ Tools.spawnClassCommand("FrameCommand",
|
|||
{"Pixmap": str(os.path.join(icondir, "frame.svg")),
|
||||
"MenuText": "Make a free frame",
|
||||
"ToolTip": "Make a freestanding reference frame."})
|
||||
|
||||
Tools.spawnClassCommand("ASM4StructureParsing",
|
||||
Asm4StructureParseUseCase().initParse,
|
||||
RobossemblerFreeCadExportScenario().call,
|
||||
{"Pixmap": str(os.path.join(icondir, "assembly4.svg")),
|
||||
"MenuText": "Make a ASM4 parsing",
|
||||
"ToolTip": "Make a ASM4 1"})
|
||||
|
|
14
cg/freecad/Frames/helper/fs.py
Normal file
14
cg/freecad/Frames/helper/fs.py
Normal file
|
@ -0,0 +1,14 @@
|
|||
import os
|
||||
import json
|
||||
|
||||
|
||||
class FS:
|
||||
def readJSON(path: str):
|
||||
return json.loads((open(path)).read())
|
||||
|
||||
def writeFile(data, filePath, fileName):
|
||||
file_to_open = filePath + fileName
|
||||
|
||||
f = open(file_to_open, 'w', )
|
||||
|
||||
f.write(data)
|
18
cg/freecad/Frames/helper/is_solid.py
Normal file
18
cg/freecad/Frames/helper/is_solid.py
Normal file
|
@ -0,0 +1,18 @@
|
|||
import FreeCAD
|
||||
|
||||
|
||||
def is_object_solid(obj):
|
||||
"""If obj is solid return True"""
|
||||
if not isinstance(obj, FreeCAD.DocumentObject):
|
||||
return False
|
||||
|
||||
if not hasattr(obj, 'Shape'):
|
||||
return False
|
||||
|
||||
if not hasattr(obj.Shape, 'Solids'):
|
||||
return False
|
||||
|
||||
if len(obj.Shape.Solids) == 0:
|
||||
return False
|
||||
|
||||
return True
|
12
cg/freecad/Frames/model/files_generator.py
Normal file
12
cg/freecad/Frames/model/files_generator.py
Normal file
|
@ -0,0 +1,12 @@
|
|||
from enum import Enum
|
||||
|
||||
|
||||
class FilesGenerator(Enum):
|
||||
DETAIL = 'detail.json'
|
||||
ASSEMBLY = 'assembly.json'
|
||||
|
||||
|
||||
class FolderGenerator(Enum):
|
||||
MESHES = 'meshes'
|
||||
ASSETS = 'assets'
|
||||
SDF = 'sdf'
|
86
cg/freecad/Frames/model/geometry_part.py
Normal file
86
cg/freecad/Frames/model/geometry_part.py
Normal file
|
@ -0,0 +1,86 @@
|
|||
from typing import Any, TypeVar, Type, cast
|
||||
|
||||
|
||||
T = TypeVar("T")
|
||||
|
||||
|
||||
def from_float(x: Any) -> float:
|
||||
assert isinstance(x, (float, int)) and not isinstance(x, bool)
|
||||
return float(x)
|
||||
|
||||
|
||||
def to_float(x: Any) -> float:
|
||||
assert isinstance(x, float)
|
||||
return x
|
||||
|
||||
|
||||
def to_class(c: Type[T], x: Any) -> dict:
|
||||
assert isinstance(x, c)
|
||||
return cast(Any, x).to_dict()
|
||||
|
||||
|
||||
class Axis:
|
||||
x: float
|
||||
y: float
|
||||
z: float
|
||||
|
||||
def __init__(self, x: float, y: float, z: float) -> None:
|
||||
self.x = x
|
||||
self.y = y
|
||||
self.z = z
|
||||
|
||||
@staticmethod
|
||||
def from_dict(obj: Any) -> 'Axis':
|
||||
assert isinstance(obj, dict)
|
||||
x = from_float(obj.get("x"))
|
||||
y = from_float(obj.get("y"))
|
||||
z = from_float(obj.get("z"))
|
||||
return Axis(x, y, z)
|
||||
|
||||
def to_dict(self) -> dict:
|
||||
result: dict = {}
|
||||
result["x"] = to_float(self.x)
|
||||
result["y"] = to_float(self.y)
|
||||
result["z"] = to_float(self.z)
|
||||
return result
|
||||
|
||||
|
||||
class GeometryPart:
|
||||
euler: Axis
|
||||
position: Axis
|
||||
rotation: Axis
|
||||
center: Axis
|
||||
|
||||
def __init__(self, euler: Axis, position: Axis, rotation: Axis, center: Axis) -> None:
|
||||
self.euler = euler
|
||||
self.position = position
|
||||
self.rotation = rotation
|
||||
self.center = center
|
||||
|
||||
@staticmethod
|
||||
def from_dict(obj: Any) -> 'GeometryPart':
|
||||
assert isinstance(obj, dict)
|
||||
euler = Axis.from_dict(obj.get("euler"))
|
||||
position = Axis.from_dict(obj.get("position"))
|
||||
rotation = Axis.from_dict(obj.get("rotation"))
|
||||
center = Axis.from_dict(obj.get("center"))
|
||||
return GeometryPart(euler, position, rotation, center)
|
||||
|
||||
def to_dict(self) -> dict:
|
||||
result: dict = {}
|
||||
result["euler"] = to_class(Axis, self.euler)
|
||||
result["position"] = to_class(Axis, self.position)
|
||||
result["rotation"] = to_class(Axis, self.rotation)
|
||||
result["center"] = to_class(Axis, self.center)
|
||||
return result
|
||||
|
||||
def toJson(self) -> str:
|
||||
return str(self.to_dict()).replace('\'', '"')
|
||||
|
||||
|
||||
def geometry_part_from_dict(s: Any) -> GeometryPart:
|
||||
return GeometryPart.from_dict(s)
|
||||
|
||||
|
||||
def geometry_part_to_dict(x: GeometryPart) -> Any:
|
||||
return to_class(GeometryPart, x)
|
107
cg/freecad/Frames/model/sdf_geometry_model.py
Normal file
107
cg/freecad/Frames/model/sdf_geometry_model.py
Normal file
|
@ -0,0 +1,107 @@
|
|||
import json
|
||||
|
||||
|
||||
def from_str(x):
|
||||
assert isinstance(x, str)
|
||||
return x
|
||||
|
||||
|
||||
def from_none(x):
|
||||
assert x is None
|
||||
return x
|
||||
|
||||
|
||||
def from_union(fs, x):
|
||||
for f in fs:
|
||||
try:
|
||||
return f(x)
|
||||
except:
|
||||
pass
|
||||
assert False
|
||||
|
||||
|
||||
def to_class(c, x):
|
||||
assert isinstance(x, c)
|
||||
return x.to_dict()
|
||||
|
||||
|
||||
class SdfGeometryModel:
|
||||
def __init__(self, name, ixx, ixy, ixz, iyy, izz, massSDF, posX, posY, posZ, eulerX, eulerY, eulerZ, iyz, stl, friction):
|
||||
self.name = name
|
||||
self.ixx = ixx
|
||||
self.ixy = ixy
|
||||
self.ixz = ixz
|
||||
self.iyy = iyy
|
||||
self.izz = izz
|
||||
self.massSDF = massSDF
|
||||
self.posX = posX
|
||||
self.posY = posY
|
||||
self.posZ = posZ
|
||||
self.eulerX = eulerX
|
||||
self.eulerY = eulerY
|
||||
self.eulerZ = eulerZ
|
||||
self.iyz = iyz
|
||||
self.stl = stl
|
||||
self.friction = friction
|
||||
|
||||
@staticmethod
|
||||
def from_dict(obj):
|
||||
assert isinstance(obj, dict)
|
||||
name = from_union([from_str, from_none], obj.get("name"))
|
||||
ixx = from_union([from_str, from_none], obj.get("ixx"))
|
||||
ixy = from_union([from_str, from_none], obj.get("ixy"))
|
||||
ixz = from_union([from_str, from_none], obj.get("ixz"))
|
||||
iyy = from_union([from_str, from_none], obj.get("iyy"))
|
||||
izz = from_union([from_str, from_none], obj.get("izz"))
|
||||
massSDF = from_union([from_str, from_none], obj.get("massSDF"))
|
||||
posX = from_union([from_str, from_none], obj.get("posX"))
|
||||
posY = from_union([from_str, from_none], obj.get("posY"))
|
||||
posZ = from_union([from_str, from_none], obj.get("posZ"))
|
||||
eulerX = from_union([from_str, from_none], obj.get("eulerX"))
|
||||
eulerY = from_union([from_str, from_none], obj.get("eulerY"))
|
||||
eulerZ = from_union([from_str, from_none], obj.get("eulerZ"))
|
||||
iyz = from_union([from_str, from_none], obj.get("iyz"))
|
||||
stl = from_union([from_str, from_none], obj.get("stl") )
|
||||
friction = from_union([from_str, from_none], obj.get("friction"))
|
||||
return SdfGeometryModel(name, ixx, ixy, ixz, iyy, izz, massSDF, posX, posY, posZ, eulerX, eulerY, eulerZ, iyz,stl,friction)
|
||||
|
||||
def to_dict(self):
|
||||
result = {}
|
||||
if self.name is not None:
|
||||
result["name"] = from_union([from_str, from_none], self.name)
|
||||
if self.ixx is not None:
|
||||
result["ixx"] = from_union([from_str, from_none], self.ixx)
|
||||
if self.ixy is not None:
|
||||
result["ixy"] = from_union([from_str, from_none], self.ixy)
|
||||
if self.ixz is not None:
|
||||
result["ixz"] = from_union([from_str, from_none], self.ixz)
|
||||
if self.iyy is not None:
|
||||
result["iyy"] = from_union([from_str, from_none], self.iyy)
|
||||
if self.izz is not None:
|
||||
result["izz"] = from_union([from_str, from_none], self.izz)
|
||||
if self.massSDF is not None:
|
||||
result["massSDF"] = from_union([from_str, from_none], self.massSDF)
|
||||
if self.posX is not None:
|
||||
result["posX"] = from_union([from_str, from_none], self.posX)
|
||||
if self.posY is not None:
|
||||
result["posY"] = from_union([from_str, from_none], self.posY)
|
||||
if self.posZ is not None:
|
||||
result["posZ"] = from_union([from_str, from_none], self.posZ)
|
||||
if self.eulerX is not None:
|
||||
result["eulerX"] = from_union([from_str, from_none], self.eulerX)
|
||||
if self.eulerY is not None:
|
||||
result["eulerY"] = from_union([from_str, from_none], self.eulerY)
|
||||
if self.eulerZ is not None:
|
||||
result["eulerZ"] = from_union([from_str, from_none], self.eulerZ)
|
||||
if self.iyz is not None:
|
||||
result["iyz"] = from_union([from_str, from_none], self.iyz)
|
||||
if self.stl is not None:
|
||||
result["stl"] = from_union([from_str, from_none], self.stl)
|
||||
if self.friction is not None:
|
||||
result["friction"] = from_union([from_str, from_none], self.eulerZ)
|
||||
return result
|
||||
|
||||
def toJSON(self) -> str:
|
||||
return str(self.to_dict()).replace('\'', '"')
|
||||
|
||||
|
|
@ -0,0 +1,70 @@
|
|||
import FreeCAD
|
||||
from usecases.export_usecase import ExportUseCase
|
||||
from usecases.get_sdf_geometry_usecase import SdfGeometryUseCase
|
||||
from usecases.assembly_parse_usecase import AssemblyParseUseCase
|
||||
from usecases.geometry_usecase import GeometryUseCase
|
||||
from model.geometry_part import GeometryPart
|
||||
from model.files_generator import FolderGenerator
|
||||
from helper.fs import FS
|
||||
from PySide import QtGui
|
||||
import os
|
||||
import ImportGui
|
||||
import shutil
|
||||
|
||||
|
||||
class RobossemblerFreeCadExportScenario:
|
||||
|
||||
def call(self):
|
||||
|
||||
path = self.qtGuiFeature()
|
||||
if path == None:
|
||||
return
|
||||
self.systemHelper(path)
|
||||
|
||||
def qtGuiFeature(self):
|
||||
if FreeCAD.ActiveDocument == None:
|
||||
FreeCAD.Console.PrintError("No active document")
|
||||
|
||||
p = QtGui.QFileDialog.getExistingDirectoryUrl()
|
||||
path = p.path()
|
||||
|
||||
if path == '':
|
||||
return None
|
||||
return path
|
||||
|
||||
def systemHelper(self, path: str):
|
||||
|
||||
root_label = FreeCAD.ActiveDocument.RootObjects[0].Label
|
||||
directory = path + '/' + root_label
|
||||
|
||||
if not os.path.exists(directory):
|
||||
os.makedirs(directory)
|
||||
|
||||
__objs__ = FreeCAD.ActiveDocument.RootObjects
|
||||
|
||||
os.makedirs(directory + '/' + FolderGenerator.ASSETS.value)
|
||||
os.makedirs(directory + '/' + FolderGenerator.SDF.value)
|
||||
os.makedirs(directory + '/' + FolderGenerator.SDF.value + '/' + FolderGenerator.MESHES.value)
|
||||
f = open(directory + "/step-structure.json", "w")
|
||||
f.write(AssemblyParseUseCase().toJson())
|
||||
f.close()
|
||||
self.geometry(directory)
|
||||
|
||||
ImportGui.export(__objs__, directory + '/' + 'assembly.step')
|
||||
|
||||
shutil.make_archive(directory, 'zip', directory)
|
||||
|
||||
shutil.rmtree(directory)
|
||||
return True
|
||||
|
||||
def geometry(self, outPutsPath: str):
|
||||
meshesExportUseCase = ExportUseCase.call(outPutsPath)
|
||||
for el in SdfGeometryUseCase.call(meshesExportUseCase):
|
||||
FS.writeFile(el.toJSON(), outPutsPath +
|
||||
'/' + FolderGenerator.ASSETS.value + '/', el.name + '.json',)
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
|
@ -1,53 +0,0 @@
|
|||
import FreeCAD as App
|
||||
|
||||
class Asm4StructureParseUseCase:
|
||||
_parts = []
|
||||
_label = []
|
||||
|
||||
def getSubPartsLabel(self, group):
|
||||
groupLabel = []
|
||||
for el in group:
|
||||
if str(el) == '<Part::PartFeature>':
|
||||
groupLabel.append(el.Label)
|
||||
return groupLabel
|
||||
|
||||
def parseLabel(self, nextGroup, label, level=2, nextGroupParse=0):
|
||||
if nextGroup.__len__() == nextGroupParse:
|
||||
return
|
||||
else:
|
||||
groupParts = []
|
||||
|
||||
for el in nextGroup:
|
||||
if str(el) == '<App::Link object>':
|
||||
groupParts.append(el)
|
||||
|
||||
for el in groupParts:
|
||||
if str(el) == '<App::Link object>':
|
||||
label.append({
|
||||
"level": level,
|
||||
"attachedTo": el.AttachedTo.split('#'),
|
||||
"label": el.Label,
|
||||
"axis": self.getSubPartsLabel(el.Group)
|
||||
})
|
||||
|
||||
def initParse(self):
|
||||
|
||||
model = App.ActiveDocument.RootObjects[1]
|
||||
self._label.append({
|
||||
"level": 1,
|
||||
"attachedTo": "Parent Assembly",
|
||||
"label": model.Label,
|
||||
"axis": self.getSubPartsLabel(model.Group)
|
||||
})
|
||||
for parent in model.Group:
|
||||
if str(parent) == '<App::Link object>':
|
||||
self._label.append({
|
||||
"level": 1,
|
||||
"attachedTo": parent.AttachedTo.split('#'),
|
||||
"label": parent.Label,
|
||||
"axis": self.getSubPartsLabel(parent.Group)
|
||||
})
|
||||
print(self._label)
|
||||
|
||||
|
||||
|
42
cg/freecad/Frames/usecases/assembly_parse_usecase.py
Normal file
42
cg/freecad/Frames/usecases/assembly_parse_usecase.py
Normal file
|
@ -0,0 +1,42 @@
|
|||
import FreeCAD as App
|
||||
from helper.is_solid import is_object_solid
|
||||
|
||||
|
||||
class AssemblyParseUseCase:
|
||||
_parts = []
|
||||
_asm = []
|
||||
|
||||
def __init__(self) -> None:
|
||||
self.initParse()
|
||||
pass
|
||||
|
||||
|
||||
|
||||
def initParse(self):
|
||||
for el in App.ActiveDocument.Objects:
|
||||
if(is_object_solid(el)):
|
||||
self._asm.append(el.Label)
|
||||
|
||||
def toJson(self):
|
||||
return str(self._asm).replace('\'', "\"")
|
||||
|
||||
def getSubPartsLink(self, group):
|
||||
groupLink = {}
|
||||
for el in group:
|
||||
if (is_object_solid(el)):
|
||||
if str(el.Shape).find('Solid') != -1:
|
||||
if groupLink.get(el.Label) == None:
|
||||
groupLink[el.Label] = []
|
||||
for i in el.Group:
|
||||
|
||||
if str(i).find('Pad') != -1:
|
||||
groupLink[el.Label].append(i)
|
||||
if groupLink.__len__() == 0:
|
||||
return None
|
||||
return groupLink
|
||||
|
||||
def getLinkedProperty(self):
|
||||
return self._asm
|
||||
|
||||
|
||||
|
16
cg/freecad/Frames/usecases/export_usecase.py
Normal file
16
cg/freecad/Frames/usecases/export_usecase.py
Normal file
|
@ -0,0 +1,16 @@
|
|||
import importDAE
|
||||
import FreeCAD as App
|
||||
from model.files_generator import FolderGenerator
|
||||
from helper.is_solid import is_object_solid
|
||||
|
||||
|
||||
class ExportUseCase:
|
||||
def call(path):
|
||||
meshes = {}
|
||||
for el in App.ActiveDocument.Objects:
|
||||
if (is_object_solid(el)):
|
||||
importDAE.export([el], path + '/' + FolderGenerator.SDF.value +
|
||||
'/' + FolderGenerator.MESHES.value + '/' + el.Label + '.dae')
|
||||
meshes[el.Label] = '/' + FolderGenerator.MESHES.value + \
|
||||
'/' + el.Label + '.dae'
|
||||
return meshes
|
54
cg/freecad/Frames/usecases/geometry_usecase.py
Normal file
54
cg/freecad/Frames/usecases/geometry_usecase.py
Normal file
|
@ -0,0 +1,54 @@
|
|||
|
||||
import FreeCAD as App
|
||||
from helper.is_solid import is_object_solid
|
||||
|
||||
|
||||
class GeometryUseCase:
|
||||
def call() -> dict:
|
||||
labels = []
|
||||
for el in App.ActiveDocument.Objects:
|
||||
|
||||
if is_object_solid(el):
|
||||
labels.append(el.Label)
|
||||
|
||||
geometry = {
|
||||
"euler": {
|
||||
"x": None,
|
||||
"y": None,
|
||||
"z": None
|
||||
},
|
||||
"position": {
|
||||
"x": None,
|
||||
"y": None,
|
||||
"z": None
|
||||
},
|
||||
"rotation": {
|
||||
"x": None,
|
||||
"y": None,
|
||||
"z": None
|
||||
},
|
||||
"center": {
|
||||
"x": None,
|
||||
"y": None,
|
||||
"z": None
|
||||
},
|
||||
|
||||
}
|
||||
|
||||
boundBox = el.Shape.BoundBox
|
||||
geometry["center"]["x"] = boundBox.Center.x
|
||||
geometry["center"]["y"] = boundBox.Center.y
|
||||
geometry["center"]["z"] = boundBox.Center.z
|
||||
geometry["position"]['x'] = boundBox.XMax
|
||||
geometry["position"]['y'] = boundBox.YMax
|
||||
geometry["position"]['z'] = boundBox.ZMax
|
||||
rotation = el.Placement.Rotation
|
||||
geometry["rotation"]['x'] = rotation.Axis.z
|
||||
geometry["rotation"]['y'] = rotation.Axis.y
|
||||
geometry["rotation"]['z'] = rotation.Axis.z
|
||||
euler = el.Placement.Rotation.toEuler()
|
||||
geometry["euler"]['x'] = euler[0]
|
||||
geometry["euler"]['y'] = euler[1]
|
||||
geometry["euler"]['z'] = euler[2]
|
||||
|
||||
return {"geometry": geometry, "labels": labels, "label": el.Label}
|
63
cg/freecad/Frames/usecases/get_sdf_geometry_usecase.py
Normal file
63
cg/freecad/Frames/usecases/get_sdf_geometry_usecase.py
Normal file
|
@ -0,0 +1,63 @@
|
|||
import FreeCAD as App
|
||||
from model.sdf_geometry_model import SdfGeometryModel
|
||||
|
||||
from helper.is_solid import is_object_solid
|
||||
|
||||
|
||||
class SdfGeometryUseCase:
|
||||
def call(stlPaths:dict) -> list[SdfGeometryModel]:
|
||||
materialSolid = {}
|
||||
for el in App.ActiveDocument.Objects:
|
||||
if str(el) == '<App::MaterialObjectPython object>':
|
||||
friction = el.Material.get('SlidingFriction')
|
||||
for i in el.References:
|
||||
materialSolid[i[0].Label] = friction
|
||||
geometry = []
|
||||
for el in App.ActiveDocument.Objects:
|
||||
if is_object_solid(el):
|
||||
com = el.Shape.CenterOfMass
|
||||
mass = el.Shape.Mass
|
||||
inertia = el.Shape.MatrixOfInertia
|
||||
pos = el.Shape.Placement
|
||||
inertia = el.Shape.MatrixOfInertia
|
||||
name = el.Label
|
||||
ixx = str(inertia.A11 / 1000000)
|
||||
ixy = str(inertia.A12 / 1000000)
|
||||
ixz = str(inertia.A13 / 1000000)
|
||||
iyy = str(inertia.A22 / 1000000)
|
||||
iyz = str(inertia.A23 / 1000000)
|
||||
izz = str(inertia.A33 / 1000000)
|
||||
massSDF = str(mass / 1000000)
|
||||
posX = str(pos.Base[0] / 1000000)
|
||||
posY = str(pos.Base[1] / 1000000)
|
||||
posZ = str(pos.Base[2] / 1000000)
|
||||
eulerX = str(pos.Rotation.toEuler()[0])
|
||||
eulerY = str(pos.Rotation.toEuler()[1])
|
||||
eulerZ = str(pos.Rotation.toEuler()[2])
|
||||
|
||||
geometry.append(
|
||||
SdfGeometryModel(
|
||||
stl=stlPaths.get(el.Label),
|
||||
name=name,
|
||||
ixx=ixx,
|
||||
ixz=ixz,
|
||||
ixy=ixy,
|
||||
iyy=iyy,
|
||||
iyz=iyz,
|
||||
izz=izz,
|
||||
massSDF=massSDF,
|
||||
posX=posX,
|
||||
posY=posY,
|
||||
posZ=posZ,
|
||||
eulerX=eulerX,
|
||||
eulerY=eulerY,
|
||||
eulerZ=eulerZ,
|
||||
friction=materialSolid.get(el.Label) or '',
|
||||
)
|
||||
)
|
||||
return geometry
|
||||
|
||||
|
||||
|
||||
|
||||
|
Loading…
Add table
Add a link
Reference in a new issue