From 8fba62e8a31d6b3982b66bd60b0fb9f37ff750cd Mon Sep 17 00:00:00 2001 From: Mark Voltov Date: Sat, 25 May 2024 12:12:11 +0300 Subject: [PATCH] =?UTF-8?q?=D0=BE=D0=B1=D0=BD=D0=BE=D0=B2=D0=BB=D0=B5?= =?UTF-8?q?=D0=BD=D0=B8=D0=B5=20=D1=84=D0=B0=D0=B9=D0=BB=D0=BE=D0=B2=20asp?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../robossembler/cad_generation/env.json | 4 +- .../helper/file_system_repository.py | 2 +- .../robossembler/cad_generation/main.py | 25 +- .../cad_generation/model/files_generator.py | 1 - .../cad_generation/model/geometry_part.py | 2 +- .../cad_generation/model/join_mesh_model.py | 2 +- .../cad_generation/model/mesh_part_model.py | 4 +- .../model/robosembler_assets.py | 141 +++ .../model/sdf_geometry_model.py | 81 +- .../model/simple_copy_part_model.py | 1 - .../robossembler_freecad_export_scenari.py | 49 +- .../usecases/asm4parser_usecase.py | 53 + .../usecases/assembly_parse_usecase.py | 3 +- .../export_assembly_them_all_usecase.py | 1 - .../cad_generation/usecases/export_usecase.py | 22 +- .../usecases/get_sdf_geometry_usecase.py | 28 +- .../cad_stability_input/.gitignore | 95 ++ .../cad_stability_input/LICENSE | 505 ++++++++++ .../cad_stability_input/README.md | 0 .../cad_stability_input/gui/__init__.py | 4 + .../cad_stability_input/gui/init_gui.py | 89 ++ .../gui/resources/server_sync.svg | 134 +++ .../gui/resources/stability_zone.svg | 142 +++ .../gui/resources/template_resource.svg | 166 ++++ .../cad_stability_input/gui/version.py | 1 + .../cad_stability_input/main.py | 47 + .../geometric_feasibility_predicate/README.MD | 2 + .../geometric_feasibility_predicate/env.json | 9 +- .../geometric_feasibility_predicate/main.py | 923 +++++++++++++++--- .../insertion_vector_predicate/.gitignore | 116 +++ .../pddl/insertion_vector_predicate/README.md | 33 + .../pddl/insertion_vector_predicate/assembly | 1 + .../insertion_vector_predicate/generate.py | 205 ++++ .../pddl/insertion_vector_predicate/main.py | 174 ++++ .../requirements.txt | 3 + insertion_vector_predicate/assembly | 1 + 36 files changed, 2804 insertions(+), 265 deletions(-) create mode 100644 freecad_workbench/freecad/robossembler/cad_generation/model/robosembler_assets.py create mode 100644 freecad_workbench/freecad/robossembler/cad_generation/usecases/asm4parser_usecase.py create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/.gitignore create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/LICENSE create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/README.md create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/__init__.py create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/init_gui.py create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/server_sync.svg create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/stability_zone.svg create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/template_resource.svg create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/version.py create mode 100644 freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/main.py create mode 100644 freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/README.MD create mode 100644 freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/.gitignore create mode 100644 freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/README.md create mode 160000 freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/assembly create mode 100644 freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/generate.py create mode 100644 freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/main.py create mode 100644 freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/requirements.txt create mode 160000 insertion_vector_predicate/assembly diff --git a/freecad_workbench/freecad/robossembler/cad_generation/env.json b/freecad_workbench/freecad/robossembler/cad_generation/env.json index f0f5724..21f4910 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/env.json +++ b/freecad_workbench/freecad/robossembler/cad_generation/env.json @@ -1,4 +1,4 @@ { - "cadFilePath": "/Users/idontsudo/Desktop/asp-example/disk_and_axis_n.FCStd", - "outPath": "/Users/idontsudo/Desktop/asp-example/" + "cadFilePath": "/home/markvoltov/GitProjects/framework/test_models/cubes.FCStd", + "outPath": "/home/markvoltov/GitProjects/framework/test_models/" } diff --git a/freecad_workbench/freecad/robossembler/cad_generation/helper/file_system_repository.py b/freecad_workbench/freecad/robossembler/cad_generation/helper/file_system_repository.py index a2419d8..92fd1d1 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/helper/file_system_repository.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/helper/file_system_repository.py @@ -23,6 +23,6 @@ class FileSystemRepository: def writeFile(data, filePath, fileName): file_to_open = filePath + fileName - f = open(file_to_open, "w", encoding="utf-8", errors="ignore") + f = open(file_to_open, "w", encoding="utf-8") f.write(data) f.close() diff --git a/freecad_workbench/freecad/robossembler/cad_generation/main.py b/freecad_workbench/freecad/robossembler/cad_generation/main.py index 24eabf7..73859f1 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/main.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/main.py @@ -1,25 +1,32 @@ import FreeCAD as App from helper.file_system_repository import FileSystemRepository from scenarios.robossembler_freecad_export_scenari import ( - RobossemblerFreeCadExportScenari, + RobossemblerFreeCadExportScenario, ) import FreeCADGui as Gui -# obj.Support[0][0].Label -# 'Hex_King' import FreeCAD as App +import os + def main(): - env = FileSystemRepository.readJSON("./env.json") - App.openDocument(env.get("cadFilePath")) - RobossemblerFreeCadExportScenari.call(env.get("outPath")) - App.closeDocument(App.ActiveDocument.Name) - freecadQTWindow = Gui.getMainWindow() - freecadQTWindow.close() + try: + print(os.path.join(os.path.dirname(__file__)) + "/env.json") + env = FileSystemRepository.readJSON( + os.path.join(os.path.dirname(__file__)) + "/env.json" + ) + App.openDocument(env.get("cadFilePath")) + RobossemblerFreeCadExportScenario.call(env.get("outPath")) + App.closeDocument(App.ActiveDocument.Name) + freecadQTWindow = Gui.getMainWindow() + freecadQTWindow.close() + except ValueError: + freecadQTWindow = Gui.getMainWindow() + freecadQTWindow.close() main() diff --git a/freecad_workbench/freecad/robossembler/cad_generation/model/files_generator.py b/freecad_workbench/freecad/robossembler/cad_generation/model/files_generator.py index ec61a0f..68b4a0b 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/model/files_generator.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/model/files_generator.py @@ -1,6 +1,5 @@ from enum import Enum -#структура файловой системы class FilesGenerator(Enum): DETAIL = 'detail.json' diff --git a/freecad_workbench/freecad/robossembler/cad_generation/model/geometry_part.py b/freecad_workbench/freecad/robossembler/cad_generation/model/geometry_part.py index 5802b98..f63f055 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/model/geometry_part.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/model/geometry_part.py @@ -44,7 +44,7 @@ class Axis: result["z"] = to_float(self.z) return result -#запись параметров тела в объект + class GeometryPart: euler: Axis position: Axis diff --git a/freecad_workbench/freecad/robossembler/cad_generation/model/join_mesh_model.py b/freecad_workbench/freecad/robossembler/cad_generation/model/join_mesh_model.py index 9de4599..52ca96b 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/model/join_mesh_model.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/model/join_mesh_model.py @@ -3,7 +3,7 @@ import Mesh import FreeCAD as App from model.mesh_part_model import MeshPartModel -# соединяет меши в сборочных единицах + class JoinMeshModel: id = None mesh = None diff --git a/freecad_workbench/freecad/robossembler/cad_generation/model/mesh_part_model.py b/freecad_workbench/freecad/robossembler/cad_generation/model/mesh_part_model.py index 1f48922..dc77871 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/model/mesh_part_model.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/model/mesh_part_model.py @@ -2,10 +2,10 @@ import FreeCAD as App import uuid import Mesh import Part -import PartGui +# import PartGui import MeshPart -#импорт мешей и превращение их в part-объекты + class MeshPartModel: id = None mesh = None diff --git a/freecad_workbench/freecad/robossembler/cad_generation/model/robosembler_assets.py b/freecad_workbench/freecad/robossembler/cad_generation/model/robosembler_assets.py new file mode 100644 index 0000000..c8e38b9 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_generation/model/robosembler_assets.py @@ -0,0 +1,141 @@ +from dataclasses import dataclass +from typing import Any, List, TypeVar, Callable, Type, cast + + +T = TypeVar("T") + + +def from_str(x: Any) -> str: + assert isinstance(x, str) + return x + + +def from_list(f: Callable[[Any], T], x: Any) -> List[T]: + assert isinstance(x, list) + return [f(y) for y in x] + + +def to_class(c: Type[T], x: Any) -> dict: + assert isinstance(x, c) + return cast(Any, x).to_dict() + + +@dataclass +class Asset: + name: str + ixx: str + ixy: str + ixz: str + iyy: str + izz: str + mass: str + posX: str + posY: str + posZ: str + eulerX: str + eulerY: str + eulerZ: str + iyz: str + meshPath: str + friction: str + centerMassX: str + centerMassY: str + centerMassZ: str + + @staticmethod + def from_dict(obj: Any) -> "Asset": + assert isinstance(obj, dict) + name = from_str(obj.get("name")) + ixx = from_str(obj.get("ixx")) + ixy = from_str(obj.get("ixy")) + ixz = from_str(obj.get("ixz")) + iyy = from_str(obj.get("iyy")) + izz = from_str(obj.get("izz")) + mass = from_str(obj.get("mass")) + posX = from_str(obj.get("posX")) + posY = from_str(obj.get("posY")) + posZ = from_str(obj.get("posZ")) + eulerX = from_str(obj.get("eulerX")) + eulerY = from_str(obj.get("eulerY")) + eulerZ = from_str(obj.get("eulerZ")) + iyz = from_str(obj.get("iyz")) + meshPath = from_str(obj.get("meshPath")) + friction = from_str(obj.get("friction")) + centerMassX = from_str(obj.get("centerMassX")) + centerMassY = from_str(obj.get("centerMassY")) + centerMassZ = from_str(obj.get("centerMassZ")) + return Asset( + name, + ixx, + ixy, + ixz, + iyy, + izz, + mass, + posX, + posY, + posZ, + eulerX, + eulerY, + eulerZ, + iyz, + meshPath, + friction, + centerMassX, + centerMassY, + centerMassZ, + ) + + def to_dict(self) -> dict: + result: dict = {} + result["name"] = from_str(self.name) + result["ixx"] = from_str(self.ixx) + result["ixy"] = from_str(self.ixy) + result["ixz"] = from_str(self.ixz) + result["iyy"] = from_str(self.iyy) + result["izz"] = from_str(self.izz) + result["mass"] = from_str(self.mass) + result["posX"] = from_str(self.posX) + result["posY"] = from_str(self.posY) + result["posZ"] = from_str(self.posZ) + result["eulerX"] = from_str(self.eulerX) + result["eulerY"] = from_str(self.eulerY) + result["eulerZ"] = from_str(self.eulerZ) + result["iyz"] = from_str(self.iyz) + result["meshPath"] = from_str(self.meshPath) + result["friction"] = from_str(self.friction) + result["centerMassX"] = from_str(self.centerMassX) + result["centerMassY"] = from_str(self.centerMassY) + result["centerMassZ"] = from_str(self.centerMassZ) + return result + + +@dataclass +class RobossemblerAssets: + assets: List[Asset] + instances: List[Any] + + @staticmethod + def from_dict(obj: Any) -> "RobossemblerAssets": + assert isinstance(obj, dict) + assets = from_list(Asset.from_dict, obj.get("assets")) + instances = from_list(lambda x: x, obj.get("instances")) + return RobossemblerAssets(assets, instances) + + def to_dict(self) -> dict: + result: dict = {} + result["assets"] = from_list(lambda x: to_class(Asset, x), self.assets) + result["instances"] = from_list(lambda x: x, self.instances) + return result + + def toJson(self) -> str: + print(self.to_dict()) + return str(self.to_dict()).replace("'", '"') + + +def RobossemblerAssetsfromdict(s: Any) -> RobossemblerAssets: + return RobossemblerAssets.from_dict(s) + + +def RobossemblerAssetstodict(x: RobossemblerAssets) -> Any: + return to_class(RobossemblerAssets, x) diff --git a/freecad_workbench/freecad/robossembler/cad_generation/model/sdf_geometry_model.py b/freecad_workbench/freecad/robossembler/cad_generation/model/sdf_geometry_model.py index ff2811a..86a6d89 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/model/sdf_geometry_model.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/model/sdf_geometry_model.py @@ -24,16 +24,37 @@ def to_class(c, x): assert isinstance(x, c) return x.to_dict() -#обработка геометрии, создание sdf + class SdfGeometryModel: - def __init__(self, name, ixx, ixy, ixz, iyy, izz, massSDF, posX, posY, posZ, eulerX, eulerY, eulerZ, iyz, stl, friction): + def __init__( + self, + name, + ixx, + ixy, + ixz, + iyy, + izz, + mass, + posX, + posY, + posZ, + eulerX, + eulerY, + eulerZ, + iyz, + meshPath, + friction, + centerMassX, + centerMassY, + centerMassZ, + ): self.name = name self.ixx = ixx self.ixy = ixy self.ixz = ixz self.iyy = iyy self.izz = izz - self.massSDF = massSDF + self.mass = mass self.posX = posX self.posY = posY self.posZ = posZ @@ -41,8 +62,11 @@ class SdfGeometryModel: self.eulerY = eulerY self.eulerZ = eulerZ self.iyz = iyz - self.stl = stl + self.meshPath = meshPath self.friction = friction + self.centerMassX = centerMassX + self.centerMassY = centerMassY + self.centerMassZ = centerMassZ @staticmethod def from_dict(obj): @@ -52,18 +76,41 @@ class SdfGeometryModel: 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")) + iyz = from_union([from_str, from_none], obj.get("iyz")) izz = from_union([from_str, from_none], obj.get("izz")) - massSDF = from_union([from_str, from_none], obj.get("massSDF")) + mass = from_union([from_str, from_none], obj.get("mass")) 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") ) + meshPath = from_union([from_str, from_none], obj.get("meshPath")) 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) + centerMassX = from_union([from_str, from_none], obj.get("centerMassX")) + centerMassY = from_union([from_str, from_none], obj.get("centerMassY")) + centerMassZ = from_union([from_str, from_none], obj.get("centerMassZ")) + return SdfGeometryModel( + name, + ixx, + ixy, + ixz, + iyy, + izz, + mass, + posX, + posY, + posZ, + eulerX, + eulerY, + eulerZ, + iyz, + meshPath, + friction, + centerMassX, + centerMassY, + centerMassZ, + ) def to_dict(self): result = {} @@ -79,8 +126,8 @@ class SdfGeometryModel: 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.mass is not None: + result["mass"] = from_union([from_str, from_none], self.mass) if self.posX is not None: result["posX"] = from_union([from_str, from_none], self.posX) if self.posY is not None: @@ -95,13 +142,17 @@ class SdfGeometryModel: 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.meshPath is not None: + result["meshPath"] = from_union([from_str, from_none], self.meshPath) if self.friction is not None: result["friction"] = from_union([from_str, from_none], self.eulerZ) + if self.centerMassX is not None: + result["centerMassX"] = from_union([from_str, from_none], self.centerMassX) + if self.centerMassY is not None: + result["centerMassY"] = from_union([from_str, from_none], self.centerMassY) + if self.centerMassZ is not None: + result["centerMassZ"] = from_union([from_str, from_none], self.centerMassZ) return result def toJSON(self) -> str: - return str(self.to_dict()).replace('\'', '"') - - \ No newline at end of file + return str(self.to_dict()).replace("'", '"') diff --git a/freecad_workbench/freecad/robossembler/cad_generation/model/simple_copy_part_model.py b/freecad_workbench/freecad/robossembler/cad_generation/model/simple_copy_part_model.py index 51f95d4..05c54f0 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/model/simple_copy_part_model.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/model/simple_copy_part_model.py @@ -16,7 +16,6 @@ class SimpleCopyPartModel: from random import randrange self.id = str(randrange(1000000)) childObj = part - print(part) __shape = Part.getShape( childObj, '', needSubElement=False, refine=False) obj = App.ActiveDocument.addObject('Part::Feature', self.id) diff --git a/freecad_workbench/freecad/robossembler/cad_generation/scenarios/robossembler_freecad_export_scenari.py b/freecad_workbench/freecad/robossembler/cad_generation/scenarios/robossembler_freecad_export_scenari.py index 7c46434..b08f050 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/scenarios/robossembler_freecad_export_scenari.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/scenarios/robossembler_freecad_export_scenari.py @@ -1,53 +1,40 @@ +from model.robosembler_assets import RobossemblerAssets 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.get_sdf_geometry_usecase import GeometryUseCase from usecases.assembly_parse_usecase import AssemblyParseUseCase from model.files_generator import FolderGenerator from helper.file_system_repository import FileSystemRepository import os +import json -class RobossemblerFreeCadExportScenari: +class RobossemblerFreeCadExportScenario: def call(path): - #работа с директорией directory = path __objs__ = FreeCAD.ActiveDocument.RootObjects directoryExport = directory + "/" - - #создание новых папок и удаление старых при их наличии согласно структуре FileSystemRepository.deletingOldAndCreatingNewFolder( - directoryExport + FolderGenerator.ASSETS.value - ) - FileSystemRepository.deletingOldAndCreatingNewFolder( - directoryExport + FolderGenerator.SDF.value, + directoryExport + FolderGenerator.MESHES.value ) - FileSystemRepository.deletingOldAndCreatingNewFolder( - directoryExport - + FolderGenerator.SDF.value - + "/" - + FolderGenerator.MESHES.value - ) - FileSystemRepository.deletingOldAndCreatingNewFolder( - directoryExport + FolderGenerator.ASSEMBlY.value - ) - f = open(directory + "/step-structure.json", "w") - f.write(AssemblyParseUseCase().toJson()) - f.close() - RobossemblerFreeCadExportScenari.geometry(directory) - ExportAssemblyThemAllUseCase().call(directoryExport) - + RobossemblerFreeCadExportScenario.geometry(directory) + ExportAssemblyThemAllUseCase().call(directoryExport) return True def geometry(outPutsPath: str): - #экспорт геометрии exportUseCase = ExportUseCase.call(outPutsPath, EXPORT_TYPES.OBJ) + # for el in GeometryUseCase().call(exportUseCase): + # FileSystemRepository.writeFile(el.toJSON(), outPutsPath + '/' + FolderGenerator.ASSETS.value + '/', el.name + '.json',) - for el in SdfGeometryUseCase().call(exportUseCase): - FileSystemRepository.writeFile( - el.toJSON(), - outPutsPath + FolderGenerator.ASSETS.value + "/", - el.name + ".json", - ) + assets = [] + for el in GeometryUseCase().call(exportUseCase): + assets.append(el) + robossemblerAssets = RobossemblerAssets(assets=assets, instances=[]).toJson() + FileSystemRepository.writeFile( + robossemblerAssets, + outPutsPath, + "robossembler_assets.json", + ) diff --git a/freecad_workbench/freecad/robossembler/cad_generation/usecases/asm4parser_usecase.py b/freecad_workbench/freecad/robossembler/cad_generation/usecases/asm4parser_usecase.py new file mode 100644 index 0000000..f732d1b --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_generation/usecases/asm4parser_usecase.py @@ -0,0 +1,53 @@ +import FreeCAD as App + +class Asm4StructureParseUseCase: + _parts = [] + _label = [] + + def getSubPartsLabel(self, group): + groupLabel = [] + for el in group: + if str(el) == '': + 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) == '': + groupParts.append(el) + + for el in groupParts: + if str(el) == '': + 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) == '': + self._label.append({ + "level": 1, + "attachedTo": parent.AttachedTo.split('#'), + "label": parent.Label, + "axis": self.getSubPartsLabel(parent.Group) + }) + print(self._label) + + + \ No newline at end of file diff --git a/freecad_workbench/freecad/robossembler/cad_generation/usecases/assembly_parse_usecase.py b/freecad_workbench/freecad/robossembler/cad_generation/usecases/assembly_parse_usecase.py index 4dc5ef0..e3b4e0d 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/usecases/assembly_parse_usecase.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/usecases/assembly_parse_usecase.py @@ -1,5 +1,4 @@ import FreeCAD as App - def is_object_solid(obj): """If obj is solid return True""" if not isinstance(obj, App.DocumentObject): @@ -19,7 +18,7 @@ def is_object_solid(obj): return True -#парсит сборку, создавая список деталей и сборочных единиц + class AssemblyParseUseCase: _parts = [] diff --git a/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_assembly_them_all_usecase.py b/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_assembly_them_all_usecase.py index 3f78975..837059a 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_assembly_them_all_usecase.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_assembly_them_all_usecase.py @@ -12,7 +12,6 @@ import os import json -#подготавливает необходимое для работы assemble them all состояние папок class ExportAssemblyThemAllUseCase: def call(self, path): assembly = AssemblyParseUseCase().getAsm() diff --git a/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_usecase.py b/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_usecase.py index 173169d..abdc92b 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_usecase.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/usecases/export_usecase.py @@ -11,39 +11,19 @@ class EXPORT_TYPES(Enum): 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.OBJ.value: import importOBJ importOBJ.export( [el], path - + "/" - + FolderGenerator.SDF.value - + "/" + FolderGenerator.MESHES.value + "/" + el.Label diff --git a/freecad_workbench/freecad/robossembler/cad_generation/usecases/get_sdf_geometry_usecase.py b/freecad_workbench/freecad/robossembler/cad_generation/usecases/get_sdf_geometry_usecase.py index 6ea2931..f3b9770 100644 --- a/freecad_workbench/freecad/robossembler/cad_generation/usecases/get_sdf_geometry_usecase.py +++ b/freecad_workbench/freecad/robossembler/cad_generation/usecases/get_sdf_geometry_usecase.py @@ -1,24 +1,28 @@ import FreeCAD as App +from model.robosembler_assets import Asset from model.sdf_geometry_model import SdfGeometryModel from helper.is_solid import is_object_solid -class SdfGeometryUseCase: - ShapePropertyCheck = ['Mass', 'MatrixOfInertia', 'Placement', ] - PartPropertyCheck = ['Shape'] +class GeometryUseCase: + ShapePropertyCheck = [ + "Mass", + "MatrixOfInertia", + "Placement", + ] + PartPropertyCheck = ["Shape"] - def call(self, stlPaths: dict) -> list[SdfGeometryModel]: + def call(self, stlPaths: dict) -> list[Asset]: materialSolid = {} for el in App.ActiveDocument.Objects: - if str(el) == '': - friction = el.Material.get('SlidingFriction') + if str(el) == "": + 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 @@ -43,8 +47,8 @@ class SdfGeometryUseCase: centerMassY = str(el.Shape.CenterOfMass[1]) centerMassZ = str(el.Shape.CenterOfMass[2]) geometry.append( - SdfGeometryModel( - stl=stlPaths.get(el.Label), + Asset( + meshPath=stlPaths.get(el.Label), name=name, ixx=ixx, ixz=ixz, @@ -52,17 +56,17 @@ class SdfGeometryUseCase: iyy=iyy, iyz=iyz, izz=izz, - massSDF=massSDF, + mass=massSDF, posX=posX, posY=posY, posZ=posZ, eulerX=eulerX, eulerY=eulerY, eulerZ=eulerZ, - friction=materialSolid.get(el.Label) or '', + friction=materialSolid.get(el.Label) or "", centerMassX=centerMassX, centerMassY=centerMassY, - centerMassZ=centerMassZ + centerMassZ=centerMassZ, ) ) except Exception as e: diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/.gitignore b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/.gitignore new file mode 100644 index 0000000..2b2f40c --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/.gitignore @@ -0,0 +1,95 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +env/ +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +*.egg-info/ +.installed.cfg +*.egg + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*,cover +.hypothesis/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# pyenv +.python-version + +# celery beat schedule file +celerybeat-schedule + +# SageMath parsed files +*.sage.py + +# dotenv +.env + +# virtualenv +.venv +venv/ +ENV/ + +# Spyder project settings +.spyderproject + +# Rope project settings +.ropeproject +env.json \ No newline at end of file diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/LICENSE b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/LICENSE new file mode 100644 index 0000000..5f2dd7f --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/LICENSE @@ -0,0 +1,505 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 2.1, February 1999 + + Copyright (C) 1991, 1999 Free Software Foundation, Inc. + 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + +(This is the first released version of the Lesser GPL. It also counts + as the successor of the GNU Library Public License, version 2, hence + the version number 2.1.) + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +Licenses are intended to guarantee your freedom to share and change +free software--to make sure the software is free for all its users. + + This license, the Lesser General Public License, applies to some +specially designated software packages--typically libraries--of the +Free Software Foundation and other authors who decide to use it. You +can use it too, but we suggest you first think carefully about whether +this license or the ordinary General Public License is the better +strategy to use in any particular case, based on the explanations below. + + When we speak of free software, we are referring to freedom of use, +not price. Our General Public Licenses are designed to make sure that +you have the freedom to distribute copies of free software (and charge +for this service if you wish); that you receive source code or can get +it if you want it; that you can change the software and use pieces of +it in new free programs; and that you are informed that you can do +these things. + + To protect your rights, we need to make restrictions that forbid +distributors to deny you these rights or to ask you to surrender these +rights. These restrictions translate to certain responsibilities for +you if you distribute copies of the library or if you modify it. + + For example, if you distribute copies of the library, whether gratis +or for a fee, you must give the recipients all the rights that we gave +you. You must make sure that they, too, receive or can get the source +code. If you link other code with the library, you must provide +complete object files to the recipients, so that they can relink them +with the library after making changes to the library and recompiling +it. And you must show them these terms so they know their rights. + + We protect your rights with a two-step method: (1) we copyright the +library, and (2) we offer you this license, which gives you legal +permission to copy, distribute and/or modify the library. + + To protect each distributor, we want to make it very clear that +there is no warranty for the free library. Also, if the library is +modified by someone else and passed on, the recipients should know +that what they have is not the original version, so that the original +author's reputation will not be affected by problems that might be +introduced by others. + + Finally, software patents pose a constant threat to the existence of +any free program. We wish to make sure that a company cannot +effectively restrict the users of a free program by obtaining a +restrictive license from a patent holder. Therefore, we insist that +any patent license obtained for a version of the library must be +consistent with the full freedom of use specified in this license. + + Most GNU software, including some libraries, is covered by the +ordinary GNU General Public License. This license, the GNU Lesser +General Public License, applies to certain designated libraries, and +is quite different from the ordinary General Public License. We use +this license for certain libraries in order to permit linking those +libraries into non-free programs. + + When a program is linked with a library, whether statically or using +a shared library, the combination of the two is legally speaking a +combined work, a derivative of the original library. The ordinary +General Public License therefore permits such linking only if the +entire combination fits its criteria of freedom. The Lesser General +Public License permits more lax criteria for linking other code with +the library. + + We call this license the "Lesser" General Public License because it +does Less to protect the user's freedom than the ordinary General +Public License. It also provides other free software developers Less +of an advantage over competing non-free programs. These disadvantages +are the reason we use the ordinary General Public License for many +libraries. However, the Lesser license provides advantages in certain +special circumstances. + + For example, on rare occasions, there may be a special need to +encourage the widest possible use of a certain library, so that it becomes +a de-facto standard. To achieve this, non-free programs must be +allowed to use the library. A more frequent case is that a free +library does the same job as widely used non-free libraries. In this +case, there is little to gain by limiting the free library to free +software only, so we use the Lesser General Public License. + + In other cases, permission to use a particular library in non-free +programs enables a greater number of people to use a large body of +free software. For example, permission to use the GNU C Library in +non-free programs enables many more people to use the whole GNU +operating system, as well as its variant, the GNU/Linux operating +system. + + Although the Lesser General Public License is Less protective of the +users' freedom, it does ensure that the user of a program that is +linked with the Library has the freedom and the wherewithal to run +that program using a modified version of the Library. + + The precise terms and conditions for copying, distribution and +modification follow. Pay close attention to the difference between a +"work based on the library" and a "work that uses the library". The +former contains code derived from the library, whereas the latter must +be combined with the library in order to run. + + GNU LESSER GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License Agreement applies to any software library or other +program which contains a notice placed by the copyright holder or +other authorized party saying it may be distributed under the terms of +this Lesser General Public License (also called "this License"). +Each licensee is addressed as "you". + + A "library" means a collection of software functions and/or data +prepared so as to be conveniently linked with application programs +(which use some of those functions and data) to form executables. + + The "Library", below, refers to any such software library or work +which has been distributed under these terms. A "work based on the +Library" means either the Library or any derivative work under +copyright law: that is to say, a work containing the Library or a +portion of it, either verbatim or with modifications and/or translated +straightforwardly into another language. (Hereinafter, translation is +included without limitation in the term "modification".) + + "Source code" for a work means the preferred form of the work for +making modifications to it. For a library, complete source code means +all the source code for all modules it contains, plus any associated +interface definition files, plus the scripts used to control compilation +and installation of the library. + + Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running a program using the Library is not restricted, and output from +such a program is covered only if its contents constitute a work based +on the Library (independent of the use of the Library in a tool for +writing it). Whether that is true depends on what the Library does +and what the program that uses the Library does. + + 1. You may copy and distribute verbatim copies of the Library's +complete source code as you receive it, in any medium, provided that +you conspicuously and appropriately publish on each copy an +appropriate copyright notice and disclaimer of warranty; keep intact +all the notices that refer to this License and to the absence of any +warranty; and distribute a copy of this License along with the +Library. + + You may charge a fee for the physical act of transferring a copy, +and you may at your option offer warranty protection in exchange for a +fee. + + 2. You may modify your copy or copies of the Library or any portion +of it, thus forming a work based on the Library, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) The modified work must itself be a software library. + + b) You must cause the files modified to carry prominent notices + stating that you changed the files and the date of any change. + + c) You must cause the whole of the work to be licensed at no + charge to all third parties under the terms of this License. + + d) If a facility in the modified Library refers to a function or a + table of data to be supplied by an application program that uses + the facility, other than as an argument passed when the facility + is invoked, then you must make a good faith effort to ensure that, + in the event an application does not supply such function or + table, the facility still operates, and performs whatever part of + its purpose remains meaningful. + + (For example, a function in a library to compute square roots has + a purpose that is entirely well-defined independent of the + application. Therefore, Subsection 2d requires that any + application-supplied function or table used by this function must + be optional: if the application does not supply it, the square + root function must still compute square roots.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Library, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Library, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote +it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Library. + +In addition, mere aggregation of another work not based on the Library +with the Library (or with a work based on the Library) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may opt to apply the terms of the ordinary GNU General Public +License instead of this License to a given copy of the Library. To do +this, you must alter all the notices that refer to this License, so +that they refer to the ordinary GNU General Public License, version 2, +instead of to this License. (If a newer version than version 2 of the +ordinary GNU General Public License has appeared, then you can specify +that version instead if you wish.) Do not make any other change in +these notices. + + Once this change is made in a given copy, it is irreversible for +that copy, so the ordinary GNU General Public License applies to all +subsequent copies and derivative works made from that copy. + + This option is useful when you wish to copy part of the code of +the Library into a program that is not a library. + + 4. You may copy and distribute the Library (or a portion or +derivative of it, under Section 2) in object code or executable form +under the terms of Sections 1 and 2 above provided that you accompany +it with the complete corresponding machine-readable source code, which +must be distributed under the terms of Sections 1 and 2 above on a +medium customarily used for software interchange. + + If distribution of object code is made by offering access to copy +from a designated place, then offering equivalent access to copy the +source code from the same place satisfies the requirement to +distribute the source code, even though third parties are not +compelled to copy the source along with the object code. + + 5. A program that contains no derivative of any portion of the +Library, but is designed to work with the Library by being compiled or +linked with it, is called a "work that uses the Library". Such a +work, in isolation, is not a derivative work of the Library, and +therefore falls outside the scope of this License. + + However, linking a "work that uses the Library" with the Library +creates an executable that is a derivative of the Library (because it +contains portions of the Library), rather than a "work that uses the +library". The executable is therefore covered by this License. +Section 6 states terms for distribution of such executables. + + When a "work that uses the Library" uses material from a header file +that is part of the Library, the object code for the work may be a +derivative work of the Library even though the source code is not. +Whether this is true is especially significant if the work can be +linked without the Library, or if the work is itself a library. The +threshold for this to be true is not precisely defined by law. + + If such an object file uses only numerical parameters, data +structure layouts and accessors, and small macros and small inline +functions (ten lines or less in length), then the use of the object +file is unrestricted, regardless of whether it is legally a derivative +work. (Executables containing this object code plus portions of the +Library will still fall under Section 6.) + + Otherwise, if the work is a derivative of the Library, you may +distribute the object code for the work under the terms of Section 6. +Any executables containing that work also fall under Section 6, +whether or not they are linked directly with the Library itself. + + 6. As an exception to the Sections above, you may also combine or +link a "work that uses the Library" with the Library to produce a +work containing portions of the Library, and distribute that work +under terms of your choice, provided that the terms permit +modification of the work for the customer's own use and reverse +engineering for debugging such modifications. + + You must give prominent notice with each copy of the work that the +Library is used in it and that the Library and its use are covered by +this License. You must supply a copy of this License. If the work +during execution displays copyright notices, you must include the +copyright notice for the Library among them, as well as a reference +directing the user to the copy of this License. Also, you must do one +of these things: + + a) Accompany the work with the complete corresponding + machine-readable source code for the Library including whatever + changes were used in the work (which must be distributed under + Sections 1 and 2 above); and, if the work is an executable linked + with the Library, with the complete machine-readable "work that + uses the Library", as object code and/or source code, so that the + user can modify the Library and then relink to produce a modified + executable containing the modified Library. (It is understood + that the user who changes the contents of definitions files in the + Library will not necessarily be able to recompile the application + to use the modified definitions.) + + b) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (1) uses at run time a + copy of the library already present on the user's computer system, + rather than copying library functions into the executable, and (2) + will operate properly with a modified version of the library, if + the user installs one, as long as the modified version is + interface-compatible with the version that the work was made with. + + c) Accompany the work with a written offer, valid for at + least three years, to give the same user the materials + specified in Subsection 6a, above, for a charge no more + than the cost of performing this distribution. + + d) If distribution of the work is made by offering access to copy + from a designated place, offer equivalent access to copy the above + specified materials from the same place. + + e) Verify that the user has already received a copy of these + materials or that you have already sent this user a copy. + + For an executable, the required form of the "work that uses the +Library" must include any data and utility programs needed for +reproducing the executable from it. However, as a special exception, +the materials to be distributed need not include anything that is +normally distributed (in either source or binary form) with the major +components (compiler, kernel, and so on) of the operating system on +which the executable runs, unless that component itself accompanies +the executable. + + It may happen that this requirement contradicts the license +restrictions of other proprietary libraries that do not normally +accompany the operating system. Such a contradiction means you cannot +use both them and the Library together in an executable that you +distribute. + + 7. You may place library facilities that are a work based on the +Library side-by-side in a single library together with other library +facilities not covered by this License, and distribute such a combined +library, provided that the separate distribution of the work based on +the Library and of the other library facilities is otherwise +permitted, and provided that you do these two things: + + a) Accompany the combined library with a copy of the same work + based on the Library, uncombined with any other library + facilities. This must be distributed under the terms of the + Sections above. + + b) Give prominent notice with the combined library of the fact + that part of it is a work based on the Library, and explaining + where to find the accompanying uncombined form of the same work. + + 8. You may not copy, modify, sublicense, link with, or distribute +the Library except as expressly provided under this License. Any +attempt otherwise to copy, modify, sublicense, link with, or +distribute the Library is void, and will automatically terminate your +rights under this License. However, parties who have received copies, +or rights, from you under this License will not have their licenses +terminated so long as such parties remain in full compliance. + + 9. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Library or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Library (or any work based on the +Library), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Library or works based on it. + + 10. Each time you redistribute the Library (or any work based on the +Library), the recipient automatically receives a license from the +original licensor to copy, distribute, link with or modify the Library +subject to these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties with +this License. + + 11. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Library at all. For example, if a patent +license would not permit royalty-free redistribution of the Library by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Library. + +If any portion of this section is held invalid or unenforceable under any +particular circumstance, the balance of the section is intended to apply, +and the section as a whole is intended to apply in other circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 12. If the distribution and/or use of the Library is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Library under this License may add +an explicit geographical distribution limitation excluding those countries, +so that distribution is permitted only in or among countries not thus +excluded. In such case, this License incorporates the limitation as if +written in the body of this License. + + 13. The Free Software Foundation may publish revised and/or new +versions of the Lesser General Public License from time to time. +Such new versions will be similar in spirit to the present version, +but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Library +specifies a version number of this License which applies to it and +"any later version", you have the option of following the terms and +conditions either of that version or of any later version published by +the Free Software Foundation. If the Library does not specify a +license version number, you may choose any version ever published by +the Free Software Foundation. + + 14. If you wish to incorporate parts of the Library into other free +programs whose distribution conditions are incompatible with these, +write to the author to ask for permission. For software which is +copyrighted by the Free Software Foundation, write to the Free +Software Foundation; we sometimes make exceptions for this. Our +decision will be guided by the two goals of preserving the free status +of all derivatives of our free software and of promoting the sharing +and reuse of software generally. + + NO WARRANTY + + 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO +WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. +EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR +OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY +KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE +LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME +THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN +WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY +AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU +FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE +LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING +RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A +FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF +SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH +DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Libraries + + If you develop a new library, and you want it to be of the greatest +possible use to the public, we recommend making it free software that +everyone can redistribute and change. You can do so by permitting +redistribution under these terms (or, alternatively, under the terms of the +ordinary General Public License). + + To apply these terms, attach the following notices to the library. It is +safest to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least the +"copyright" line and a pointer to where the full notice is found. + + {description} + Copyright (C) {year} {fullname} + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 + USA + +Also add information on how to contact you by electronic and paper mail. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the library, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the + library `Frob' (a library for tweaking knobs) written by James Random + Hacker. + + {signature of Ty Coon}, 1 April 1990 + Ty Coon, President of Vice + +That's all there is to it! + diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/README.md b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/README.md new file mode 100644 index 0000000..e69de29 diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/__init__.py b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/__init__.py new file mode 100644 index 0000000..f80dcdc --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/__init__.py @@ -0,0 +1,4 @@ +import os +from .version import __version__ + +ICONPATH = os.path.join(os.path.dirname(__file__), "resources") diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/init_gui.py b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/init_gui.py new file mode 100644 index 0000000..65c0bdb --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/init_gui.py @@ -0,0 +1,89 @@ +import os +import FreeCADGui as Gui +import FreeCAD as App +from PySide.QtCore import QT_TRANSLATE_NOOP +import shutil +ICONPATH = os.path.join(os.path.dirname(__file__), "resources") +zone = "StabilityZone" +import requests +import importOBJ + + +class AddStabilityZone: + def __init__(self): + pass + + def GetResources(self): + return {'Pixmap': os.path.join(ICONPATH, "stability_zone.svg"), + 'Accel': "Ctrl+A", + 'MenuText': QT_TRANSLATE_NOOP("My_Command", "My Command"), + 'ToolTip': QT_TRANSLATE_NOOP("My_Command", "Runs my command in the active document")} + + def Activated(self): + App.ActiveDocument.addObject("Part::Box", "Box") + App.ActiveDocument.ActiveObject.Label = zone + selected_object = App.ActiveDocument.getObjectsByLabel(zone)[0] + selected_object.ViewObject.Transparency = 50 + selected_object.ViewObject.ShapeColor = (0.15, 0.80, 0.50) + pass + + def IsActive(self): + return True + + +class SyncServer: + + httpURL = None + def __init__(self, httpURL): + self.httpURL = httpURL + + + def GetResources(self): + return {'Pixmap': os.path.join(ICONPATH, "server_sync.svg"), + 'Accel': "Ctrl+A", + 'MenuText': QT_TRANSLATE_NOOP("My_Command", "My Command"), + 'ToolTip': QT_TRANSLATE_NOOP("My_Command", "Runs my command in the active document")} + + def Activated(self): + StabilityZone = App.ActiveDocument.getObjectsByLabel(zone) + dir_path = os.path.dirname(os.path.realpath(__file__)) + dir_out = dir_path + '/out/' + if not os.path.exists(dir_out): + os.makedirs(dir_out) + importOBJ.export(StabilityZone, u"" + dir_out + 'StabilityZone.obj') + shutil.make_archive(dir_out + '/' + 'geometry', 'zip',) + zipArch = dir_out + 'geometry.zip' + requests.post(url=self.httpURL, files={'zip': open(zipArch, "rb")}) + shutil.rmtree(dir_out) + pass + + def IsActive(self): + return True + + +class StabilityWorkbench(Gui.Workbench): + + MenuText = "stability workbench" + ToolTip = "a simple template workbench" + Icon = os.path.join(ICONPATH, "template_resource.svg") + toolbox = ['AddStabilityZone', 'SyncServer'] + httpURL = None + def __init__(self,httpURL): + self.httpURL = httpURL + + + def GetClassName(self): + return "Gui::PythonWorkbench" + + def Initialize(self): + Gui.addCommand('AddStabilityZone', AddStabilityZone()) + Gui.addCommand('SyncServer', SyncServer( + self.httpURL)) + self.appendToolbar("Tools", self.toolbox) + self.appendMenu("Tools", self.toolbox) + + def Activated(self): + pass + + def Deactivated(self): + pass diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/server_sync.svg b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/server_sync.svg new file mode 100644 index 0000000..da595a2 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/server_sync.svg @@ -0,0 +1,134 @@ + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/stability_zone.svg b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/stability_zone.svg new file mode 100644 index 0000000..3f7686a --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/stability_zone.svg @@ -0,0 +1,142 @@ + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + + + + + + + + + + + + + + + + diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/template_resource.svg b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/template_resource.svg new file mode 100644 index 0000000..509be26 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/resources/template_resource.svg @@ -0,0 +1,166 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + + + + + + T + diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/version.py b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/version.py new file mode 100644 index 0000000..3486632 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/gui/version.py @@ -0,0 +1 @@ +__version__ = "0.8.1" \ No newline at end of file diff --git a/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/main.py b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/main.py new file mode 100644 index 0000000..e0bb99d --- /dev/null +++ b/freecad_workbench/freecad/robossembler/cad_stability_input/cad_stability_input/main.py @@ -0,0 +1,47 @@ +import os +import FreeCADGui as Gui +import FreeCAD as App +from gui.init_gui import StabilityWorkbench +import json + + +def importObjAtPath(path: str): + import importOBJ + importOBJ.insert(u"" + path, App.ActiveDocument.Label) + + pass + + +def getFullPathObj(assemblyFolder: str, name: str): + return assemblyFolder + 'sdf/meshes/' + name + '.obj' + + +def main(): + App.newDocument() + env = json.loads((open('./env.json')).read()) + assemblyFolder = env.get('assemblyFolder') + assemblyStructure = json.loads( + (open(assemblyFolder + 'step-structure.json')).read()) + assemblyNumber = int(env.get('buildNumber')) - 1 + activeDetail = assemblyStructure[assemblyNumber] + + subassemblyNotParticipatingInMarkup = assemblyStructure[0:assemblyNumber - 1] + detailOfTheMarkingZoneOfWhich = assemblyStructure[assemblyNumber - 1] + importObjAtPath(getFullPathObj(assemblyFolder, activeDetail)) + importObjAtPath(getFullPathObj( + assemblyFolder, detailOfTheMarkingZoneOfWhich)) + meshMark = App.ActiveDocument.Objects[0] + meshDetailOfTheMarkZone = App.ActiveDocument.Objects[1] + meshMark.ViewObject.ShapeColor = (0.31, 0.77, 0.87) + meshDetailOfTheMarkZone.ViewObject.ShapeColor = (0.68, 0.66, 0.95) + for el in list(map(lambda el: getFullPathObj(assemblyFolder, el), subassemblyNotParticipatingInMarkup)): + importObjAtPath(el) + for el in App.ActiveDocument.Objects[2:App.ActiveDocument.Objects.__len__()]: + el.ViewObject.ShapeColor = (0.32, 0.05, 0.38) + Gui.SendMsgToActiveView("ViewSelection") + + Gui.addWorkbench(StabilityWorkbench(env.get('resultURL'))) + Gui.activateWorkbench("StabilityWorkbench") + + +main() diff --git a/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/README.MD b/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/README.MD new file mode 100644 index 0000000..60daaf6 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/README.MD @@ -0,0 +1,2 @@ +/Users/idontsudo/Desktop/FreeCAD.app/Contents/MacOS/FreeCAD +freecadcmd main.py \ No newline at end of file diff --git a/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/env.json b/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/env.json index ecc3e53..bcd23a5 100644 --- a/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/env.json +++ b/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/env.json @@ -1,8 +1,5 @@ { - "cadFilePath": "/home/markvoltov/TestFolder/bottle_jack/bottle_jack.FCStd", - "outPath": "/home/markvoltov/TestFolder/bottle_jack/", - "solidBodyPadding": 3, - "firstDetail": "Куб", - "sequencesFixed": [], - "restrictionsOnFasteners": [] + "cadFilePath": "/home/markvoltov/GitProjects/framework/test_models/cubes.FCStd", + "outPath": "/home/markvoltov/GitProjects/framework/test_models/", + "objectIndentation": 0 } diff --git a/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/main.py b/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/main.py index f11e36a..690bc2a 100644 --- a/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/main.py +++ b/freecad_workbench/freecad/robossembler/geometric_feasibility_predicate/main.py @@ -1,169 +1,774 @@ +import FreeCAD as App +import uuid import os -from extensions.list import CoreList -from extensions.dict import CoreDict -from helpers.freecadtest import FreeCadASPGenerationTestController -from models.adjacency_matrix_model import ( - AdjacencyMatrixModel, -) -from usecases.check_object_has_touches_use_case import ( - CheckObjectHasTouchesUseCase, -) -from usecases.clusterisation_sequences_use_case import ( - ClusterisationSequenceUseCase, -) -from usecases.check_sequence_use_case import ( - CheckSequenceUsecase, -) -from usecases.env_reader_use_case import ( - EnvReaderUseCase, -) -from usecases.exit_freecad_use_case import ( - ExitFreeCadUseCase, -) -from usecases.intersection_geometry_use_case import ( - IntersectionGeometryUseCase, -) -from usecases.open_freecad_document_use_case import ( - OpenFreeCadDocumentUseCase, -) +import json +from typing import List, Dict, Any, TypeVar, Callable, Type, cast +from itertools import repeat -from mocks.mock_structure import bottle_jack_mock_structure, simple_cube_mock_structure +class CoreList(List): + # the list contains only True + def onlyTrue(self) -> bool: + print(self) + for el in self: + if el is not True: + return False + return True +def isInListRange(listIn, index): + try: + listIn[index] + return False + except: + return True + + +class AllSequences: + all_sequences = None + adj_matrix = None + topologyIds = None + adj_matrix_names = None + + def __init__(self, adj_matrix) -> None: + self.adj_matrix = adj_matrix + self.all_possible_sequences(self.adj_matrix) + self.matrix_by_name() + pass + + def matrix_by_name(self): + result = self.all_sequences + inc = 0 + for matrix in self.all_sequences: + for index in range(len(matrix)): + result[inc][index] = list( + filter( + lambda el: el.get("number") == matrix[index] + 1, + self.topologyIds, + ) + )[0].get("name") + inc += 1 + self.adj_matrix_names = result + pass + + def find_all_sequences(self, adj_matrix): + sequences = [] + num_vertices = len(adj_matrix) + + def dfs(vertex, sequence): + sequence.append(vertex) + + if len(sequence) == num_vertices: + sequences.append(sequence) + return + + for i in range(num_vertices): + if adj_matrix[vertex][i] == 1 and i not in sequence: + dfs(i, sequence.copy()) + + for i in range(num_vertices): + dfs(i, []) + + self.all_sequences = sequences + + def findId(self, listMatrix, id): + def filter_odd_num(in_num): + if in_num["name"] == id: + return True + else: + return False + + return list(filter(filter_odd_num, listMatrix))[0]["number"] + + def iter_paths(self, adj, min_length=6, path=None): + if not path: + for start_node in range(len(adj)): + yield from self.iter_paths(adj, min_length, [start_node]) + else: + if len(path) >= min_length: + yield path + if path[-1] in path[:-1]: + return + current_node = path[-1] + for next_node in range(len(adj[current_node])): + if adj[current_node][next_node] == 1: + yield from self.iter_paths(adj, min_length, path + [next_node]) + + def allUnique(self, x): + seen = set() + return not any(i in seen or seen.add(i) for i in x) + + def all_possible_sequences(self, matrix): + topologyIds = [] + topologyMatrixNumber = {} + inc = 0 + for k, v in matrix.items(): + inc += 1 + topologyIds.append({"name": k, "number": inc}) + inc = 0 + for k, v in matrix.items(): + inc += 1 + topologyMatrixNumber[inc] = list( + map(lambda el: self.findId(topologyIds, el), v) + ) + self.topologyIds = topologyIds + adj = [] + matrixSize = matrix.keys().__len__() + inc = 0 + for k, v in topologyMatrixNumber.items(): + adj.append(list(repeat(0, matrixSize))) + for el in v: + adj[inc][el - 1] = 1 + inc += 1 + return self.find_all_sequences(adj) + + +class VectorModel: + x: float + y: float + z: float + + def __init__(self, cadVector) -> None: + self.x = cadVector[0] + self.y = cadVector[1] + self.z = cadVector[2] + pass + + def toFreeCadVector(self): + return App.Vector(self.x, self.y, self.z) + + +class FreeCadRepository: + _solids = [] + + def isAllObjectsSolids(self) -> List[str]: + result = [] + for part in App.ActiveDocument.Objects: + if self.is_object_solid(part) is False: + result.append(part.Label) + return result + + def objectSetPosition(self, solid, cadVector): + solid.Placement.Base = cadVector + pass + + def objectGetPosition(self, solid) -> VectorModel: + return VectorModel(cadVector=solid.Placement.Base) + + def isObjectIntersections(self, part) -> bool: + for solid in self.getAllSolids(): + if solid.Label != part.Label: + collisionResult: int = int(part.Shape.distToShape(solid.Shape)[0]) + if collisionResult == 0: + return True + return False + + def objectHasTouches(self, part, objectIndentation: float) -> List[str]: + positionVector = self.objectGetPosition(part) + result = CoreList() + result.append(self.isObjectIntersections(part=part)) + + if objectIndentation != 0 and objectIndentation != None: + result.append( + self.axis_movement_and_intersections_observer( + positionVector=positionVector, + alongAxis="x", + objectIndentation=objectIndentation, + part=part, + ) + ) + result.append( + self.axis_movement_and_intersections_observer( + positionVector=positionVector, + alongAxis="y", + objectIndentation=objectIndentation, + part=part, + ) + ) + result.append( + self.axis_movement_and_intersections_observer( + positionVector=positionVector, + alongAxis="z", + objectIndentation=objectIndentation, + part=part, + ) + ) + + return result.onlyTrue() + + def axis_movement_and_intersections_observer( + self, + positionVector: VectorModel, + alongAxis: str, + objectIndentation: float, + part, + ) -> bool: + # UP + positionVector.__setattr__( + alongAxis, positionVector.__getattribute__(alongAxis) + objectIndentation + ) + self.objectSetPosition(part, positionVector.toFreeCadVector()) + result = self.isObjectIntersections(part=part) + if result: + return True + # DOWN + positionVector.__setattr__( + alongAxis, positionVector.__getattribute__(alongAxis) - objectIndentation + ) + positionVector.__setattr__( + alongAxis, positionVector.__getattribute__(alongAxis) - objectIndentation + ) + result = self.isObjectIntersections(part=part) + if result: + return True + self.isObjectIntersections(part=part) + # ROLLBACK + positionVector.__setattr__( + alongAxis, positionVector.__getattribute__(alongAxis) + objectIndentation + ) + self.objectSetPosition(part, positionVector.toFreeCadVector()) + return False + + def getAllSolids(self): + if self._solids.__len__() == 0: + for part in App.ActiveDocument.Objects: + if self.is_object_solid(part): + self._solids.append(part) + + return self._solids + + def is_object_solid(self, obj): + 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, "Solids"): + return False + + if len(obj.Shape.Solids) == 0: + return False + + return True + + +T = TypeVar("T") + + +def from_list(f: Callable[[Any], T], x: Any) -> List[T]: + assert isinstance(x, list) + return [f(y) for y in x] + + +def from_str(x: Any) -> str: + assert isinstance(x, str) + return x + + +def from_dict(f: Callable[[Any], T], x: Any) -> Dict[str, T]: + assert isinstance(x, dict) + return {k: f(v) for (k, v) in x.items()} + + +def to_class(c: Type[T], x: Any) -> dict: + assert isinstance(x, c) + return cast(Any, x).to_dict() + + +# Вспомогательный класс который делает генрацию JSON на основе пайтон обьектов + + +class AdjacencyMatrix: + matrixError: Dict[str, str] = {} + all_parts: List[str] + first_detail: str + matrix: Dict[str, List[str]] + + def __init__( + self, all_parts: List[str], first_detail: str, matrix: Dict[str, List[str]] + ) -> None: + self.all_parts = all_parts + self.first_detail = first_detail + self.matrix = matrix + self.validateMatrix() + + def whatPlaceLeadingPartIndex(self): + i = 0 + for el in self.matrix: + if el == self.first_detail: + return i + i = +1 + + def validateMatrix(self): + for el in self.all_parts: + if self.matrix.get(el) == None: + self.matrixError[el] = "Not found adjacency " + el + + @staticmethod + def from_dict(obj: Any) -> "AdjacencyMatrix": + assert isinstance(obj, dict) + all_pars = from_list(from_str, obj.get("allParts")) + first_detail = from_str(obj.get("firstDetail")) + matrix = from_dict(lambda x: from_list(from_str, x), obj.get("matrix")) + + return AdjacencyMatrix(all_pars, first_detail, matrix) + + def to_dict(self) -> dict: + result: dict = {} + result["allParts"] = from_list(from_str, self.all_parts) + result["firstDetail"] = from_str(self.first_detail) + result["matrix"] = from_dict(lambda x: from_list(from_str, x), self.matrix) + if self.matrixError.values().__len__() == 0: + result["matrixError"] = None + else: + result["matrixError"] = self.matrixError + return result + + def getDictMatrix(self) -> dict: + result = {} + + for k, v in self.matrix.items(): + result[k] = {} + for el in v: + result[k][el] = el + + return result + + +def adjacency_matrix_from_dict(s: Any) -> AdjacencyMatrix: + return AdjacencyMatrix.from_dict(s) + + +def adjacency_matrix_to_dict(x: AdjacencyMatrix) -> Any: + return to_class(AdjacencyMatrix, x) + + +# Вспомогательный класс для работы с Freecad + + +class FreeCadMetaModel(object): + def __init__(self, label, vertex) -> None: + self.label = label + self.vertex = vertex + + +collision_squares_labels = [] + + +class MeshGeometryCoordinateModel(object): + # Получение геометрии мешей + def __init__( + self, + x, + y, + z, + label, + ): + self.x = x + self.y = y + self.z = z + self.label = label + self.cadLabel = "" + + def initializePrimitivesByCoordinate(self, detailSquares): + uuidDoc = str(uuid.uuid1()) + App.ActiveDocument.addObject("Part::Box", "Box") + App.ActiveDocument.ActiveObject.Label = uuidDoc + App.ActiveDocument.recompute() + part = App.ActiveDocument.getObjectsByLabel(uuidDoc)[0] + collision_squares_labels.append(uuidDoc) + part.Width = 2 + part.Height = 2 + part.Length = 2 + part.Placement = App.Placement( + App.Vector(self.x - 1, self.y - 1, self.z - 1), + App.Rotation(App.Vector(0.00, 0.00, 1.00), 0.00), + ) + if detailSquares.get(self.label) is None: + detailSquares[self.label] = [] + detailSquares[self.label].append(self) + self.cadLabel = uuidDoc + App.ActiveDocument.recompute() + + +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="utf8") + + f.write(data) + + def readFile(path: str): + return open(path).read() + + def readFilesTypeFolder(pathFolder: str, fileType=".json"): + filesJson = list( + filter( + lambda x: x[-fileType.__len__() :] == fileType, os.listdir(pathFolder) + ) + ) + return filesJson + + +class GetAllPartsLabelsUseCase: + # Получение всех названий деталей + def call(self): + parts = [] + for part in FreeCadRepository().getAllSolids(): + parts.append(part.Label) + return parts + + +def isUnique(array, element): + for i in array: + if i == element: + return False + + return True + + +class GetCollisionAtPrimitiveUseCase(object): + # Получение колизий примитивов + def call(self, freeCadMetaModels, detailSquares) -> Dict[str, List[str]]: + matrix: Dict[str, List[str]] = {} + for model in freeCadMetaModels: + activePart = App.ActiveDocument.getObjectsByLabel(model.label)[0] + for key in detailSquares: + if model.label != key: + for renderPrimitive in detailSquares[key]: + primitivePart = App.ActiveDocument.getObjectsByLabel( + renderPrimitive.cadLabel + )[0] + collisionResult: int = int( + activePart.Shape.distToShape(primitivePart.Shape)[0] + ) + if collisionResult == 0: + if matrix.get(model.label) == None: + matrix[model.label] = [renderPrimitive.label] + else: + if isUnique(matrix[model.label], renderPrimitive.label): + matrix[model.label].append(renderPrimitive.label) + return matrix + + +class GetFirstDetailUseCase: + # Получение первой детали + def call(self): + return FreeCadRepository().getAllSolids()[0].Label + + +class GetPartPrimitiveCoordinatesUseCase(object): + # Получение координат примитивов + def call(self, freeCadMetaModels): + meshCoordinates: list[MeshGeometryCoordinateModel] = [] + for model in freeCadMetaModels: + vertexesDetail = model.vertex + labelDetail = model.label + for coords in vertexesDetail: + detailVertex = MeshGeometryCoordinateModel( + coords.X, + coords.Y, + coords.Z, + labelDetail, + ) + meshCoordinates.append(detailVertex) + + return meshCoordinates + + +class InitPartsParseUseCase: + # Инициализация парсинга + def call(self): + product_details = [] + for part in FreeCadRepository().getAllSolids(): + if part is not None: + model = FreeCadMetaModel(part.Label, part.Shape.Vertexes) + if model is not None: + product_details.append(model) + return product_details + + +class RenderPrimitiveUseCase(object): + # Рендеринг премитивов + def call( + self, meshModels: list[MeshGeometryCoordinateModel], detailSquares + ) -> None: + for mesh in meshModels: + mesh.initializePrimitivesByCoordinate(detailSquares) + + +class ClearWorkSpaceDocumentUseCase(object): + # Очистка рабочего простарнства + def call(self, detailSquares): + for key in detailSquares: + for renderPrimitive in detailSquares[key]: + primitivePart = App.ActiveDocument.getObjectsByLabel( + renderPrimitive.cadLabel + )[0] + App.ActiveDocument.removeObject(primitivePart.Name) + + +class RenderPrimitivesScenario(object): + def __init__( + self, + initPartsParseUseCase: InitPartsParseUseCase, + getPartPrimitiveCoordinatesUseCase: GetPartPrimitiveCoordinatesUseCase, + renderPrimitiveUseCase: RenderPrimitiveUseCase, + getCollisionAtPrimitives: GetCollisionAtPrimitiveUseCase, + clearWorkSpaceDocument: ClearWorkSpaceDocumentUseCase, + ) -> None: + self.initPartsParseUseCase = initPartsParseUseCase + self.getPartPrimitiveCoordinatesUseCase = getPartPrimitiveCoordinatesUseCase + self.renderPrimitiveUseCase = renderPrimitiveUseCase + self.getCollisionAtPrimitives = getCollisionAtPrimitives + self.clearWorkSpaceDocument = clearWorkSpaceDocument + + def call(self) -> None: + meshCoordinates = [] + detailSquares = {} + parts = self.initPartsParseUseCase.call() + meshCoordinates = self.getPartPrimitiveCoordinatesUseCase.call(parts) + self.renderPrimitiveUseCase.call(meshCoordinates, detailSquares) + matrix = self.getCollisionAtPrimitives.call(parts, detailSquares) + self.clearWorkSpaceDocument.call(detailSquares) + return matrix + + +class ClearWorkSpaceDocumentUseCase(object): + # Очистака рабочего пространства + def call(self, detailSquares): + for key in detailSquares: + for renderPrimitive in detailSquares[key]: + primitivePart = App.ActiveDocument.getObjectsByLabel( + renderPrimitive.cadLabel + )[0] + App.ActiveDocument.removeObject(primitivePart.Name) + + +class CadAdjacencyMatrix: + # Матрица основанная на соприкосновении примитива с обьектами + def primitiveMatrix(self): + # Получение матрицы + matrix = RenderPrimitivesScenario( + InitPartsParseUseCase(), + GetPartPrimitiveCoordinatesUseCase(), + RenderPrimitiveUseCase(), + GetCollisionAtPrimitiveUseCase(), + ClearWorkSpaceDocumentUseCase(), + ).call() + return AdjacencyMatrix( + all_parts=GetAllPartsLabelsUseCase().call(), + first_detail=GetFirstDetailUseCase().call(), + matrix=matrix, + ) + + # Матрица основанная на соприкосновении обьектов + + def matrixBySurfaces(self): + matrix = {} + for part in FreeCadRepository().getAllSolids(): + matrix[part.Label] = [] + for nextPart in FreeCadRepository().getAllSolids(): + if part.Label != nextPart.Label: + # Вычисление соприконсоновения площади деталей + collisionResult: int = int( + part.Shape.distToShape(nextPart.Shape)[0] + ) + print(collisionResult) + print("collisionResult") + if collisionResult == 0: + matrix[part.Label].append(nextPart.Label) + + return AdjacencyMatrix( + all_parts=GetAllPartsLabelsUseCase().call(), + first_detail=GetFirstDetailUseCase().call(), + matrix=matrix, + ) + + +def reduce(function, iterable, initializer=None): + it = iter(iterable) + if initializer is None: + value = next(it) + else: + value = initializer + for element in it: + value = function(value, element) + return value + + +def to_ascii_hash(text): + ascii_values = [ord(character) for character in text] + return reduce(lambda x, y: x + y, ascii_values) + + +def matrixGetUniqueContact(matrix): + detailsToCheck = [] + detailsHashCheck = {} + for k, v in matrix.items(): + for el in v: + if el != k: + hash = to_ascii_hash(k + el) + if detailsHashCheck.get(hash) == None: + detailsHashCheck[hash] = hash + detailsToCheck.append({"child": el, "parent": k}) + return detailsToCheck + + +class IntersectionComputedUseCase: + def call(parts): + App.activeDocument().addObject("Part::MultiCommon", "Common") + App.activeDocument().Common.Shapes = [parts[0], parts[1]] + App.activeDocument().getObject("Common").ViewObject.ShapeColor = getattr( + parts[0].getLinkedObject(True).ViewObject, + "ShapeColor", + App.activeDocument().getObject("Common").ViewObject.ShapeColor, + ) + App.activeDocument().getObject("Common").ViewObject.DisplayMode = getattr( + parts[0].getLinkedObject(True).ViewObject, + "DisplayMode", + App.activeDocument().getObject("Common").ViewObject.DisplayMode, + ) + App.ActiveDocument.recompute() + area = App.activeDocument().getObject("Common").Shape.Area + App.ActiveDocument.removeObject("Common") + return area + + +class ErrorStringModel: + def __init__(self, error: str) -> None: + self.error = error + pass + + error: str + + def toString(self) -> str: + return json.dumps( + { + "error": self.error, + }, + ensure_ascii=False, + indent=4, + ) + + +class IsAllObjectSolidsCheckUseCase: + def call() -> ErrorStringModel: + result = FreeCadRepository().isAllObjectsSolids() + if result.__len__() == 0: + return None + + return ErrorStringModel(error="Is not solid objects: " + ",".join(result)) + + +class CheckObjectHasTouchesUseCase: + def call(objectIndentation: float) -> ErrorStringModel: + result = [] + for part in FreeCadRepository().getAllSolids(): + if ( + FreeCadRepository().objectHasTouches( + part=part, objectIndentation=objectIndentation + ) + is False + ): + result.append(part.Label) + if result.__len__() == 0: + return None + return ErrorStringModel( + error="Solids bodies have no recounts: " + ",".join(result) + ) + + +class CheckCadIntersectionObjects: + report = [] + + def call() -> bool: + FreeCadRepository().getAllSolids() + return False + + +class ExitFreeCadUseCase: + def call(): + import FreeCADGui as Gui + + freecadQTWindow = Gui.getMainWindow() + freecadQTWindow.close() + + +# class CheckValidIntersectionUseCase: +# def call() -> ErrorStringModel: +# for part in FreeCadRepository().getAllSolids(): +# print(part) +# FreeCadRepository().obj +# pass + def main(): - try: - EnvReaderUseCase.call().either( - leftF=lambda environment: ( - OpenFreeCadDocumentUseCase.call(environment.cadFilePath).either( - leftF=lambda _: ( - ( - CheckObjectHasTouchesUseCase() - .call(environment.solidBodyPadding) - .either( - leftF=lambda adjaxedMatrix: ( - adjaxedMatrix.sequencesToFileSystem( - environment.outPath, - environment.sequencesFixed, - ), - IntersectionGeometryUseCase.call( - adjaxedMatrix.matrixGetUniqueContact(), - environment.outPath, - ), - adjaxedMatrix.matrixToFileSystem( - environment.outPath, - ), - ClusterisationSequenceUseCase(environment.outPath), - ExitFreeCadUseCase.call(), - ), - rightF=lambda error: error.toFileSystem( - environment.outPath - ), - ), - ) - ), - rightF=lambda error: print(error), - ), - ), - rightF=lambda error: print(error), - ) + env = FS.readJSON("env.json") + cadFilePath = str(env["cadFilePath"]) + outPath = str(env["outPath"]) + objectIndentation = float(env["objectIndentation"]) - except Exception as error: - print(error) - ExitFreeCadUseCase.call() + if cadFilePath == None: + return TypeError("CadFile not found env.json") + App.open("" + cadFilePath) + + # isAllObjectSolidsCheckUseCase = IsAllObjectSolidsCheckUseCase.call() + + # if isAllObjectSolidsCheckUseCase != None: + # FS.writeFile(isAllObjectSolidsCheckUseCase.toString(), outPath, 'error.json') + # ExitFreeCadUseCase.call() + # return + + # checkObjectHasTouchesUseCase = CheckObjectHasTouchesUseCase.call(objectIndentation) + + # if checkObjectHasTouchesUseCase != None: + # FS.writeFile(checkObjectHasTouchesUseCase.toString(), outPath, 'error.json') + # ExitFreeCadUseCase.call() + # return + + topologyMatrix = CadAdjacencyMatrix().matrixBySurfaces() + import json + + sequences = json.dumps( + {"sequences": AllSequences(topologyMatrix.matrix).adj_matrix_names}, + ensure_ascii=False, + indent=4, + ) + matrix = topologyMatrix.matrix + contacts = matrixGetUniqueContact(matrix) + intersection_geometry = {"status": True, "recalculations": None} + for el in contacts: + child = App.ActiveDocument.getObjectsByLabel(el.get("child"))[0] + parent = App.ActiveDocument.getObjectsByLabel(el.get("parent"))[0] + area = IntersectionComputedUseCase.call([child, parent]) + if area != 0.0: + if intersection_geometry.get("recalculations") == None: + intersection_geometry["status"] = False + intersection_geometry["recalculations"] = [] + intersection_geometry["recalculations"].append( + {"area": area, "connect": el.get("child") + " " + el.get("parent")} + ) + + FS.writeFile( + json.dumps(intersection_geometry, ensure_ascii=False, indent=4), + outPath, + "intersection_geometry.json", + ) + FS.writeFile(sequences, outPath, "sequences.json") + + FS.writeFile( + json.dumps(topologyMatrix.to_dict(), ensure_ascii=False, indent=4), + outPath, + "adjacency_matrix.json", + ) + ExitFreeCadUseCase.call() -# main() - - -def test(): - try: - mocksFolder = os.path.dirname(__file__) + "/mocks/" - - outFolder = os.path.dirname(__file__) + "/out/" - - FreeCadASPGenerationTestController("test adjaxed matrix simple cube").test( - assertFn=lambda model: CoreList(model.all_parts).equal( - simple_cube_mock_structure - ), - execComposition=lambda _: ( - CheckObjectHasTouchesUseCase() - .call(0) - .either( - leftF=lambda matrix: matrix.matrixToFileSystem(outFolder), - rightF=lambda error: print(error), - ) - ), - documentPath=mocksFolder + "simple_assembly_with_two_cubes.FCStd", - modelName=AdjacencyMatrixModel.fileName, - model=AdjacencyMatrixModel, - ) - - FreeCadASPGenerationTestController( - "test adjaxed matrix vs structure of document" - ).test( - assertFn=lambda model: CoreDict(model.matrix).isEquivalentByKeys( - bottle_jack_mock_structure - ), - execComposition=lambda _: ( - CheckObjectHasTouchesUseCase() - .call(0) - .either( - leftF=lambda matrix: matrix.matrixToFileSystem(outFolder), - rightF=lambda error: print(error), - ) - ), - documentPath=mocksFolder + "bottle_jack.FCStd", - modelName=AdjacencyMatrixModel.fileName, - model=AdjacencyMatrixModel, - ) - - FreeCadASPGenerationTestController( - "test adjacency matrix keys vs allparts" - ).test( - assertFn=lambda model: CoreDict(model.matrix).isMatchByKeys( - model.all_parts - ), - execComposition=lambda _: ( - CheckObjectHasTouchesUseCase() - .call(0) - .either( - leftF=lambda matrix: (matrix.matrixToFileSystem(outFolder)), - rightF=lambda error: print(error), - ) - ), - documentPath=mocksFolder + "bottle_jack.FCStd", - modelName=AdjacencyMatrixModel.fileName, - model=AdjacencyMatrixModel, - ) - - FreeCadASPGenerationTestController("test all parts vs assembly sequence").test( - assertFn=lambda model: CheckSequenceUsecase( - ClusterisationSequenceUseCase(outFolder) - ).isCorrectByParts(model.all_parts), - execComposition=lambda _: ( - CheckObjectHasTouchesUseCase() - .call(0) - .either( - leftF=lambda matrix: ( - matrix.matrixToFileSystem(outFolder), - ClusterisationSequenceUseCase(outFolder), - ), - rightF=lambda error: print(error), - ) - ), - documentPath=mocksFolder + "bottle_jack.FCStd", - modelName=AdjacencyMatrixModel.fileName, - model=AdjacencyMatrixModel, - ) - - ExitFreeCadUseCase.call() - except Exception as e: - print(e) - print("test error") - ExitFreeCadUseCase.call() - pass - - -test() +main() diff --git a/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/.gitignore b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/.gitignore new file mode 100644 index 0000000..4a47d9e --- /dev/null +++ b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/.gitignore @@ -0,0 +1,116 @@ +# Byte-compiled / optimized / DLL files +__pycache__/ +*.py[cod] +*$py.class + +# C extensions +*.so + +# Distribution / packaging +.Python +env/ +build/ +develop-eggs/ +dist/ +downloads/ +eggs/ +.eggs/ +lib/ +lib64/ +parts/ +sdist/ +var/ +wheels/ +*.egg-info/ +.installed.cfg +*.egg + +# PyInstaller +# Usually these files are written by a python script from a template +# before PyInstaller builds the exe, so as to inject date/other infos into it. +*.manifest +*.spec + +# Installer logs +pip-log.txt +pip-delete-this-directory.txt + +# Unit test / coverage reports +htmlcov/ +.tox/ +.coverage +.coverage.* +.cache +nosetests.xml +coverage.xml +*.cover +.hypothesis/ + +# Translations +*.mo +*.pot + +# Django stuff: +*.log +local_settings.py + +# Flask stuff: +instance/ +.webassets-cache + +# Scrapy stuff: +.scrapy + +# Sphinx documentation +docs/_build/ + +# PyBuilder +target/ + +# Jupyter Notebook +.ipynb_checkpoints + +# pyenv +.python-version + +# celery beat schedule file +celerybeat-schedule + +# SageMath parsed files +*.sage.py + +# dotenv +.env + +# virtualenv +.venv +venv/ +ENV/ + +# Spyder project settings +.spyderproject +.spyproject + +# Rope project settings +.ropeproject + +# mkdocs documentation +/site + +# mypy +.mypy_cache/ + +# blender backup files +*.blend1 +install_plugin_cad.sh +.vscode +.DS_Store + +# emacs backup files +~* +*~ +*# +.#* +\#*\# +out/ +/env.json \ No newline at end of file diff --git a/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/README.md b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/README.md new file mode 100644 index 0000000..24d4b44 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/README.md @@ -0,0 +1,33 @@ +# Start dev +create env.json + +```json +{ + "cadDoc":"CAD_DOC_PATH_REPLACE", + "sequences":"SEQUENCES_PATH_REPLACE", + "aspDir":"ASP_DIR_REPLACE" +} +``` +# Command generation assets +freecad generate.py + +# Command generation insertion vectors + +git submodule update --init +conda env create -f assembly/environment.yml +conda activate assembly +python assembly/simulation/setup.py install +sudo apt-get install libgl1-mesa-dev xorg-dev +python3 main.py + + + +# Последовательность действий + +1. cad_generation main.py + 1. в env json прописываем пути +2. geometric_feasibility_predicate main.py + 1. в env json прописываем пути + +3. insertion vector predicate main.py #исправить пути к моделям в main.py +4. результат : траектории вставки \ No newline at end of file diff --git a/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/assembly b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/assembly new file mode 160000 index 0000000..395ee5b --- /dev/null +++ b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/assembly @@ -0,0 +1 @@ +Subproject commit 395ee5b638ccaa0cbe5b48101655560e49365195 diff --git a/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/generate.py b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/generate.py new file mode 100644 index 0000000..c08adb3 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/generate.py @@ -0,0 +1,205 @@ + + +from typing import List +import FreeCAD as App +import Part +import Mesh +import Part +import MeshPart +import os +import json +import FreeCADGui as Gui + +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() + def createFolder(path: str): + if (not os.path.exists(path)): + return os.mkdir(path) + + + +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 + print(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) + +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) + + + +class JoinMeshModel: + id = None + mesh = None + + def __init__(self, meshesPartModels: list['MeshPartModel']) -> None: + meshes = [] + from random import randrange + for el in meshesPartModels: + meshes.append(el.mesh.Mesh) + + self.id = 'MergedMesh' + str(randrange(1000000)) + doc = App.ActiveDocument + merged_mesh = Mesh.Mesh() + for el in meshes: + merged_mesh.addMesh(el) + + new_obj = doc.addObject("Mesh::Feature", self.id) + new_obj.Mesh = merged_mesh + new_obj.ViewObject.DisplayMode = "Flat Lines" + self.mesh = new_obj + + def remove(self): + try: + App.ActiveDocument.removeObject(self.id) + except Exception as e: + print(e) + + +class ExportAssemblyThemAllUseCase: + + def call(self, path:str, assemblys:list[str]): + assembly = assemblys + 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) + + 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 + str(1) + '.obj') + joinMesh.remove() + importOBJ.export(v['child'], path + str(0) + '.obj') + FS.writeFile(json.dumps(geometry), path, 'translation.json') + + App.ActiveDocument.removeObject("Compound") + for el in copyLinks: + el.remove() + App.activeDocument().recompute() + inc += 1 + +def main(): + + env = FS.readJSON('./env.json') + env.get('cadDoc') + aspDir = env.get('aspDir') + sequences = FS.readJSON(env.get('sequences')).get('sequences') + App.openDocument(env.get('cadDoc')) + for sequencyNumber in range(len(sequences)): + FS.createFolder(aspDir + 'assemblys/') + mainFolder = aspDir + 'assemblys/' + str(sequencyNumber) + '/' + FS.createFolder(mainFolder) + for subSequenceNumber in range(len(sequences[sequencyNumber])): + if(subSequenceNumber != 0): + subFolder = aspDir + 'assemblys/' + \ + str(sequencyNumber) + '/' + str(subSequenceNumber) + '/' + + FS.createFolder(subFolder) + ExportAssemblyThemAllUseCase().call(path=subFolder,assemblys=sequences[sequencyNumber][0:subSequenceNumber+1]) + + App.closeDocument(App.ActiveDocument.Name) + freecadQTWindow = Gui.getMainWindow() + freecadQTWindow.close() +main() \ No newline at end of file diff --git a/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/main.py b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/main.py new file mode 100644 index 0000000..b2fd134 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/main.py @@ -0,0 +1,174 @@ +import os +import sys + +project_base_dir = os.path.abspath(os.path.join( + os.path.dirname(os.path.abspath(__file__)), './')) + '/assembly/' + + +sys.path.append(project_base_dir) +sys.path.append(project_base_dir + '/baselines/') +sys.path.append(project_base_dir + '/assets/') + +from scipy.spatial.transform import Rotation +import shutil +from spatialmath import * +from spatialmath.base import * +from assembly.assets.process_mesh import process_mesh +from assembly.examples.run_joint_plan import get_planner +from assembly.baselines.run_joint_plan import PyPlanner +from assembly.assets.subdivide import subdivide_to_size +import numpy as np +import json +import trimesh + +import re +def merge_meshes(meshes): + # Создание пустого меша + merged_mesh = trimesh.Trimesh() + + # Объединение каждого меша в один + for mesh in meshes: + merged_mesh = trimesh.util.concatenate( + [merged_mesh, trimesh.load(mesh)]) + i = True + while i: + if merged_mesh.fill_holes(): + i = False + + + + + + return merged_mesh + + +os.environ['OMP_NUM_THREADS'] = '1' + + + +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) + + def readFile(path: str): + return open(path).read() + + def readFilesTypeFolder(pathFolder: str, fileType='.json'): + return os.listdir(pathFolder) + + def readFolder(pathFolder: str): + return list(map(lambda el: pathFolder + '/' + el, os.listdir(pathFolder))) + + def createFolder(path: str): + if (not os.path.exists(path)): + return os.mkdir(path) + + +def listGetFirstValue(iterable, default=False, pred=None): + return next(filter(pred, iterable), default) + + +def filterModels(filterModels, filterModelsDescription): + models = [] + for el in filterModelsDescription: + models.append(listGetFirstValue( + filterModels, None, lambda x: x.name == el)) + return models + + +# mesh1 = trimesh.load('/Users/idontsudo/framework/asp/out/sdf-generation/meshes/Cube.obj') +# mesh2 = trimesh.load('/Users/idontsudo/framework/asp/out/sdf-generation/meshes/Cube001.obj') + + +# # Объединение мешей +# merged_mesh = merge_meshes([mesh1, mesh2]) + +# # Сохранение объединенного меша в файл +# merged_mesh.export('merged.obj') +def main(): + # from argparse import ArgumentParser + # parser = ArgumentParser() + # parser.add_argument('--asp-path', type=str, required=True) + # args = parser.parse_args() + # aspDir = args.asp_dir + + # # Коректировка пути до папки с генерацией ASP + # if (aspDir == None): + # args.print_helper() + # if (aspDir[aspDir.__len__() - 1] != '/'): + # aspDir += '/' + aspDir = "/home/markvoltov/GitProjects/framework/test_models/" + sequences = FS.readJSON(aspDir + 'sequences.json').get('sequences') + + assemblyDirNormalize = [] + for el in FS.readFolder(aspDir + 'assemblys'): + for e in FS.readFolder(el): + try: + # Пост обработка .obj обьектов + process_mesh(source_dir=e, target_dir=e + + '/process/', subdivide=e, verbose=True) + assemblyDirNormalize.append(e + '/process/') + except Exception as e: + print('ERRROR:') + print(e) + + + print(assemblyDirNormalize) + for el in assemblyDirNormalize: + asset_folder = os.path.join(project_base_dir, aspDir) + assembly_dir = os.path.join(asset_folder, el) + planner = get_planner('bfs')(assembly_dir, assembly_dir, 0, [ + 1], False, 'sdf', 0.05, 0.01, 100, 100, True) + + # Планирование пути + status, t_plan, path = planner.plan( + 120, seed=1, return_path=True, render=False, record_path=None + ) + coords = [] + + for k in path: + seMatrix = SE3(k) + euler = seMatrix.eul() + coord = seMatrix.A[0:3, 3] + rot = Rotation.from_euler('xyz', euler, degrees=True).as_quat() + coords.append({'quadrelion': [rot[0], rot[1], rot[2], rot[3]], 'xyz': [ + coord[0], coord[1], coord[2]], 'euler': [euler[0], euler[1], euler[2]]}) + # Запись пути в кортеж + planingObject = { + "time": t_plan, + "insertion_path": coords, + "status": status, + } + # Запись результата планирования + FS.writeFile(json.dumps(planingObject), + el[0:el.__len__() - 8], 'insertion_path.json') + + try: + planner = PyPlanner(assembly_dir, 'process', still_ids=[1],) + status, t_plan, path = planner.plan( + planner_name='rrt', + step_size=None, + max_time=None, + seed=1, + return_path=True, + simplify=False, + render=False + ) + + print(f'Status: {status}, planning time: {t_plan}') + + if args.save_dir is not None: + planner.save_path(path, args.save_dir, args.n_save_state) + except Exception as e: + print(e) + + +main() diff --git a/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/requirements.txt b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/requirements.txt new file mode 100644 index 0000000..9f14b84 --- /dev/null +++ b/freecad_workbench/freecad/robossembler/pddl/insertion_vector_predicate/requirements.txt @@ -0,0 +1,3 @@ +spatialmath-python +scipy +uuid \ No newline at end of file diff --git a/insertion_vector_predicate/assembly b/insertion_vector_predicate/assembly new file mode 160000 index 0000000..395ee5b --- /dev/null +++ b/insertion_vector_predicate/assembly @@ -0,0 +1 @@ +Subproject commit 395ee5b638ccaa0cbe5b48101655560e49365195