Веб интерфейс для корректировки работы ASP, его интеграция с алгоритмами генерации

This commit is contained in:
IDONTSUDO 2023-07-04 07:19:55 +00:00 committed by Igor Brylyov
parent 23edfea360
commit c1e4b0e0f0
57 changed files with 2969 additions and 290 deletions

6
cad_generation/env.json Normal file
View file

@ -0,0 +1,6 @@
{
"doc": "/home/idontsudo/t/framework/asp-review-app/server/public/cubes/cubes.FCStd",
"out": "/home/idontsudo/t/framework/cad_generation",
"resultURL": "http://localhost:3002/assembly/save/out",
"projectId": "cubes"
}

View file

@ -0,0 +1,15 @@
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', encoding='utf-8',
errors='ignore')
f.write(data)
f.close()

View 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

19
cad_generation/main.py Normal file
View file

@ -0,0 +1,19 @@
import requests
import FreeCAD as App
from helper.fs import FS
from scenarios.robossembler_freecad_export_scenario import RobossemblerFreeCadExportScenario
import shutil
import os
import FreeCADGui as Gui
def main():
env = FS.readJSON('./env.json')
App.openDocument(env.get('doc'))
RobossemblerFreeCadExportScenario().call(env.get('out'))
# requests.post(url=env.get('resultURL'), files={'zip': open(env.get('out') + '/' + 'generation.zip', "rb"), 'id':env.get('projectId')})
# os.remove('./generation.zip')
App.closeDocument(App.ActiveDocument.Name)
freecadQTWindow = Gui.getMainWindow()
freecadQTWindow.close()
main()

View file

@ -0,0 +1,13 @@
from enum import Enum
class FilesGenerator(Enum):
DETAIL = 'detail.json'
ASSEMBLY = 'assembly.json'
class FolderGenerator(Enum):
MESHES = 'meshes'
ASSETS = 'assets'
SDF = 'sdf'
ASSEMBlY = 'assembly'

View 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)

View file

@ -0,0 +1,33 @@
import FreeCAD
import Mesh
import FreeCAD as App
from model.mesh_part_model import MeshPartModel
class JoinMeshModel:
id = None
mesh = None
def __init__(self, meshesPartModels: list['MeshPartModel']) -> None:
meshes = []
import Mesh
from random import randrange
for el in meshesPartModels:
meshes.append(el.mesh.Mesh)
self.id = 'MergedMesh' + str(randrange(1000000))
document = App.ActiveDocument
merged_mesh = Mesh.Mesh()
for el in meshes:
merged_mesh.addMesh(el)
new_obj = App.activeDocument().addObject("Mesh::Feature", self.id)
new_obj.Mesh = merged_mesh
new_obj.ViewObject.DisplayMode = "Flat Lines" # Set display mode to flat lines
self.mesh = new_obj
def remove(self):
try:
App.ActiveDocument.removeObject(self.id)
except Exception as e:
print(e)

View file

@ -0,0 +1,32 @@
import FreeCAD as App
import uuid
import Mesh
import Part
# import PartGui
import MeshPart
class MeshPartModel:
id = None
mesh = None
def __init__(self, part) -> None:
try:
from random import randrange
self.id = 'mesh' + str(randrange(1000000))
document = App.ActiveDocument
mesh = document.addObject("Mesh::Feature", self.id)
shape = Part.getShape(part, "")
mesh.Mesh = MeshPart.meshFromShape(
Shape=shape, LinearDeflection=20, AngularDeflection=0.1, Relative=False)
mesh.Label = self.id
self.mesh = mesh
except Exception as e:
print(e)
pass
def remove(self):
try:
App.ActiveDocument.removeObject(self.mesh.Label)
except Exception as e:
print(e)

View 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('\'', '"')

View file

@ -0,0 +1,30 @@
import FreeCAD as App
import Part
class SimpleCopyPartModel:
id = None
copyLink = None
label = None
part = None
def getPart(self):
return self.part
def __init__(self, part) -> None:
try:
from random import randrange
self.id = str(randrange(1000000))
childObj = part
__shape = Part.getShape(
childObj, '', needSubElement=False, refine=False)
obj = App.ActiveDocument.addObject('Part::Feature', self.id)
obj.Shape = __shape
self.part = obj
self.label = obj.Label
App.ActiveDocument.recompute()
except Exception as e:
print(e)
def remove(self):
App.ActiveDocument.removeObject(self.label)

View file

@ -0,0 +1,54 @@
from usecases.export_assembly_them_all_usecase import ExportAssemblyThemAllUseCase
import FreeCAD
from usecases.export_usecase import EXPORT_TYPES, 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
import os
# import ImportGui
import shutil
class RobossemblerFreeCadExportScenario:
def call(self, path):
directory = path + '/' + 'generation'
if os.path.exists(directory):
shutil.rmtree(directory)
if not os.path.exists(directory):
os.makedirs(directory)
__objs__ = FreeCAD.ActiveDocument.RootObjects
directoryExport = directory + '/'
os.makedirs(directoryExport + FolderGenerator.ASSETS.value)
os.makedirs(directoryExport + FolderGenerator.SDF.value)
os.makedirs(directoryExport + FolderGenerator.SDF.value + '/' + FolderGenerator.MESHES.value)
os.makedirs(directoryExport + FolderGenerator.ASSEMBlY.value)
f = open(directory + "/step-structure.json", "w")
f.write(AssemblyParseUseCase().toJson())
f.close()
self.geometry(directory)
ExportAssemblyThemAllUseCase().call(directoryExport)
shutil.make_archive(directory, 'zip', directory)
shutil.rmtree(directory)
return True
def geometry(self, outPutsPath: str):
exportUseCase = ExportUseCase.call(outPutsPath,EXPORT_TYPES.OBJ)
for el in SdfGeometryUseCase().call(exportUseCase):
FS.writeFile(el.toJSON(), outPutsPath + '/' + FolderGenerator.ASSETS.value + '/', el.name + '.json',)

View file

@ -0,0 +1,53 @@
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)

View file

@ -0,0 +1,58 @@
import FreeCAD as App
def is_object_solid(obj):
"""If obj is solid return True"""
if not isinstance(obj, App.DocumentObject):
return False
if hasattr(obj, 'Group'):
return False
if not hasattr(obj, 'Shape'):
return False
# if not hasattr(obj.Shape, 'Mass'):
# return False
if not hasattr(obj.Shape, 'Solids'):
return False
if len(obj.Shape.Solids) == 0:
return False
return True
class AssemblyParseUseCase:
_parts = []
_asm = []
def getAsm(self):
return self._asm
def __init__(self) -> None:
if (self._asm.__len__() == 0):
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

View file

@ -0,0 +1,92 @@
from typing import List
import FreeCAD as App
import Part
from model.join_mesh_model import JoinMeshModel
from model.mesh_part_model import MeshPartModel
from helper.fs import FS
from helper.is_solid import is_object_solid
from model.simple_copy_part_model import SimpleCopyPartModel
from model.files_generator import FolderGenerator
from usecases.assembly_parse_usecase import AssemblyParseUseCase
import os
import json
class ExportAssemblyThemAllUseCase:
def call(self, path):
assembly = AssemblyParseUseCase().getAsm()
asmStructure = {}
inc = 0
for el in assembly:
if (inc != 0):
asmStructure[inc] = {
"child": el,
"parents": assembly[0:inc]
}
inc += 1
objectsFreeCad = App.ActiveDocument.Objects
asmSolids = {}
for k, v in asmStructure.items():
assemblyParentList = v['parents']
assemblyChild = v['child']
for el in assemblyParentList:
for solid in objectsFreeCad:
if (el == solid.Label):
if (asmSolids.get(k) is None):
asmSolids[k] = {'parents': [], 'child': list(
filter(lambda x: x.Label == assemblyChild, objectsFreeCad))[0]}
asmSolids[k]['parents'].append(solid)
inc = 0
for k, v in asmSolids.items():
geometry = {"0": [], "1": []}
if (k != 0):
App.activeDocument().addObject("Part::Compound", "Compound")
copyLinks = list(
map(lambda el: SimpleCopyPartModel(el), v['parents']))
if copyLinks != None:
App.activeDocument().Compound.Links = list(
map(lambda el: el.getPart(), copyLinks))
object = App.activeDocument().getObject('Compound')
boundBox = object.Shape.BoundBox
geometry['0'].append(boundBox.XMax)
geometry['0'].append(boundBox.YMax)
geometry['0'].append(boundBox.ZMax)
os.makedirs(
path + FolderGenerator.ASSEMBlY.value + '/' + '0000' + str(k))
boundBoxChild = v['child'].Shape.BoundBox
geometry['1'].append(boundBoxChild.XMax)
geometry['1'].append(boundBoxChild.YMax)
geometry['1'].append(boundBoxChild.ZMax)
meshParents = []
for el in v['parents']:
meshParents.append(MeshPartModel(el))
joinMesh = JoinMeshModel(meshParents)
for el in meshParents:
el.remove()
import importOBJ
importOBJ.export(joinMesh.mesh, path + FolderGenerator.ASSEMBlY.value +
'/' + '0000' + str(k) + '/' + str(1) + '.obj')
joinMesh.remove()
importOBJ.export(v['child'], path + FolderGenerator.ASSEMBlY.value +
'/' + '0000' + str(k) + '/' + str(0) + '.obj')
FS.writeFile(json.dumps(geometry), path + FolderGenerator.ASSEMBlY.value +
'/' + '0000' + str(k) + '/', 'translation.json')
App.ActiveDocument.removeObject("Compound")
for el in copyLinks:
el.remove()
App.activeDocument().recompute()
inc += 1

View file

@ -0,0 +1,36 @@
# import importDAE
import Mesh
import FreeCAD as App
from model.files_generator import FolderGenerator
from helper.is_solid import is_object_solid
from enum import Enum
class EXPORT_TYPES(Enum):
STL = 'STL'
DAO = 'DAO'
OBJ = 'OBJ'
class ExportUseCase:
def call(path: str, type: EXPORT_TYPES):
meshes = {}
for el in App.ActiveDocument.Objects:
if (is_object_solid(el)):
match type.value:
case EXPORT_TYPES.STL.value:
Mesh.export([el], path + '/' + FolderGenerator.SDF.value +
'/' + FolderGenerator.MESHES.value + '/' + el.Label + '.stl')
meshes[el.Label] = '/' + FolderGenerator.MESHES.value + \
'/' + el.Label + '.stl'
# case EXPORT_TYPES.DAO.value:
# importDAE.export([el], path + '/' + FolderGenerator.SDF.value +
# '/' + FolderGenerator.MESHES.value + '/' + el.Label + '.dae')
case EXPORT_TYPES.OBJ.value:
import importOBJ
importOBJ.export([el], path + '/' + FolderGenerator.SDF.value +
'/' + FolderGenerator.MESHES.value + '/' + el.Label + '.obj')
meshes[el.Label] = '/' + FolderGenerator.MESHES.value + \
'/' + el.Label + '.obj'
print(300)
return meshes

View file

@ -0,0 +1,58 @@
import FreeCAD as App
from helper.is_solid import is_object_solid
class GeometryUseCase:
def call() -> dict:
labels = []
Error = False
for el in App.ActiveDocument.Objects:
try:
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]
except Exception as e:
print(e)
# App.Console.PrintMessage("Clicked on position: ("+str(pos[0])+", "+str(pos[1])+")\n")
return {"geometry": geometry, "labels": labels, "label": el.Label}

View file

@ -0,0 +1,68 @@
import FreeCAD as App
from model.sdf_geometry_model import SdfGeometryModel
from helper.is_solid import is_object_solid
class SdfGeometryUseCase:
ShapePropertyCheck = ['Mass','MatrixOfInertia','Placement', ]
PartPropertyCheck = ['Shape']
def call(self, 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 = []
try:
for el in App.ActiveDocument.Objects:
if is_object_solid(el):
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 '',
)
)
except Exception as e:
print(200)
return geometry