Add PDDL, 3D-assets & SDF-URDF generator from Blender Scene Config
This commit is contained in:
parent
b77687ea14
commit
e305d486f2
41 changed files with 2793 additions and 664 deletions
|
@ -26,7 +26,28 @@ def to_class(c, x):
|
|||
|
||||
|
||||
class SdfGeometryModel:
|
||||
def __init__(self, name, ixx, ixy, ixz, iyy, izz, massSDF, posX, posY, posZ, eulerX, eulerY, eulerZ, iyz, stl, friction, centerMassX, centerMassY, centerMassZ,):
|
||||
def __init__(
|
||||
self,
|
||||
name,
|
||||
ixx,
|
||||
ixy,
|
||||
ixz,
|
||||
iyy,
|
||||
izz,
|
||||
massSDF,
|
||||
posX,
|
||||
posY,
|
||||
posZ,
|
||||
eulerX,
|
||||
eulerY,
|
||||
eulerZ,
|
||||
iyz,
|
||||
stl,
|
||||
friction,
|
||||
centerMassX,
|
||||
centerMassY,
|
||||
centerMassZ,
|
||||
):
|
||||
self.name = name
|
||||
self.ixx = ixx
|
||||
self.ixy = ixy
|
||||
|
@ -69,7 +90,27 @@ class SdfGeometryModel:
|
|||
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, massSDF, posX, posY, posZ, eulerX, eulerY, eulerZ, iyz, stl, friction, centerMassX, centerMassY, centerMassZ)
|
||||
return SdfGeometryModel(
|
||||
name,
|
||||
ixx,
|
||||
ixy,
|
||||
ixz,
|
||||
iyy,
|
||||
izz,
|
||||
massSDF,
|
||||
posX,
|
||||
posY,
|
||||
posZ,
|
||||
eulerX,
|
||||
eulerY,
|
||||
eulerZ,
|
||||
iyz,
|
||||
stl,
|
||||
friction,
|
||||
centerMassX,
|
||||
centerMassY,
|
||||
centerMassZ,
|
||||
)
|
||||
|
||||
def to_dict(self):
|
||||
result = {}
|
||||
|
@ -105,14 +146,13 @@ class SdfGeometryModel:
|
|||
result["stl"] = from_union([from_str, from_none], self.stl)
|
||||
if self.friction is not None:
|
||||
result["friction"] = from_union([from_str, from_none], self.eulerZ)
|
||||
|
||||
if self.centerMassX is not None:
|
||||
result['centerMassX'] = from_union([from_str, from_none], self.centerMassX)
|
||||
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)
|
||||
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)
|
||||
result["centerMassZ"] = from_union([from_str, from_none], self.centerMassZ)
|
||||
return result
|
||||
|
||||
def toJSON(self) -> str:
|
||||
return str(self.to_dict()).replace('\'', '"')
|
||||
return str(self.to_dict()).replace("'", '"')
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue