Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix exporting scaled meshes - add link pose to sdf export #344

Open
wants to merge 3 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
8 changes: 8 additions & 0 deletions phobos/blender/io/blender2phobos.py
Original file line number Diff line number Diff line change
Expand Up @@ -430,11 +430,19 @@ def deriveLink(obj, objectlist=None, logging=True, errors=None):
annotations[k1] = {}
annotations[k1][k2] = v

root = obj
while sUtils.getEffectiveParent(root) is not None:
root = sUtils.getEffectiveParent(root)

# Exporting pose relative to root link because gazebo 9 ignores relative_to attribute
# Remove originRoot in a future update

return representation.Link(
name=obj.get("link/name", obj.name), # this is for backwards compatibility normally the linkname should be the object name
visuals=visuals,
collisions=collisions,
inertial=inertial,
originRoot=deriveObjectPose(obj, effectiveparent=root),
# [TODO v2.1.0] Add KCCD support
kccd_hull=None,
**annotations
Expand Down
2 changes: 1 addition & 1 deletion phobos/data/xml_formats.json
Original file line number Diff line number Diff line change
Expand Up @@ -653,7 +653,7 @@
"children": {
"pose": {
"classname": "Pose",
"varname": "origin"
"varname": "originRoot"
},
"inertial": {
"classname": "Inertial",
Expand Down
11 changes: 7 additions & 4 deletions phobos/io/representation.py
Original file line number Diff line number Diff line change
Expand Up @@ -1104,17 +1104,19 @@ def apply_scale(self):
elif BPY_AVAILABLE and isinstance(self.mesh_object, bpy.types.Mesh):
from ..blender.utils import blender as bUtils
objname = "tmp_export_" + self.unique_name
tmpobject = bUtils.createPrimitive(objname, 'box', self.scale)
tmpobject = bUtils.createPrimitive(objname, 'box', (1,1,1))
tmpobject.scale = self.scale
# copy the mesh here
tmpobject.data = self.mesh_object
tmpobject.data = self.mesh_object.copy()
bpy.ops.object.select_all(action='DESELECT')
tmpobject.select_set(True)
bpy.ops.object.transform_apply(scale=True)
bpy.ops.object.select_all(action='DESELECT')
tmpobject.select_set(True)
self.mesh_object = tmpobject.data
bpy.ops.object.delete()
else:
raise NotImplentedError()
raise NotImplementedError()

self._operations.append("apply_scale")
self.history.append(f"apply_scale {self.scale}")
Expand Down Expand Up @@ -1551,11 +1553,12 @@ def from_collision(self, coll, npoints=None, iv_mesh=None, kccd_path=None):
class Link(Representation, SmurfBase):
_class_variables = ["name", "visuals", "collisions", "inertial", "kccd_hull", "origin"]

def __init__(self, name=None, visuals=None, inertial=None, collisions=None, origin=None,
def __init__(self, name=None, visuals=None, inertial=None, collisions=None, origin=None, originRoot=None,
noDataPackage=None, reducedDataPackage=None, is_human=None, kccd_hull=None, joint=None, **kwargs):
SmurfBase.__init__(self, **kwargs)
self.name = name
self.origin = _singular(origin)
self.originRoot = _singular(originRoot)
self.is_human = is_human
self.returns += ['name', "is_human"]
self.visuals = _plural(visuals)
Expand Down