Skip to content
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
2 changes: 0 additions & 2 deletions phobos/blender/model/joints.py
Original file line number Diff line number Diff line change
Expand Up @@ -206,8 +206,6 @@ def setJointConstraints(
# set constraints accordingly
joint['joint/limits/lower'] = lower
joint['joint/limits/upper'] = upper
joint.data.bones.active = joint.pose.bones[0].bone
joint.data.bones.active.select = True
if jointtype == 'revolute':
set_revolute(joint, lower, upper)
elif jointtype == 'continuous':
Expand Down
118 changes: 115 additions & 3 deletions phobos/blender/model/links.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,46 +44,158 @@ def getGeometricElements(link):


def deriveLinkfromObject(obj, scale=1, parent_link=True, parent_objects=True,


reparent_children=True, nameformat='', scaleByBoundingBox=False):


"""Derives a link from an object using its name, transformation and parenting.





Args:


obj(bpy_types.Object): object to derive a link from


scale(float, optional): scale factor for bone size (Default value = 1)


parent_link(bool, optional): whether to automate the parenting of the new link or not. (Default value = True)


parent_objects(bool, optional): whether to parent all the objects to the new link or not (Default value = False)


nameformat(str, optional): re-formatting template for obj names (Default value = '')





Returns:


: newly created link





"""


log('Deriving link from ' + nUtils.getObjectName(obj), level="INFO")


# create armature/bone


bUtils.toggleLayer('link', True)


bpy.ops.object.select_all(action='DESELECT')


bpy.ops.object.armature_add()


newlink = bpy.context.active_object


newlink.name = obj.name + "_link"
newlink.matrix_world = obj.matrix_world





# This is the robust way: copy parent and local transform (matrix_basis)


# This correctly handles cases where transforms have been applied to children


if obj.parent and parent_link:


newlink.parent = obj.parent


newlink.matrix_basis = obj.matrix_basis.copy()





newlink.phobostype = 'link'


if scaleByBoundingBox:


bound_box = (


max([c[0] for c in obj.bound_box]),


max([c[1] for c in obj.bound_box]),


max([c[2] for c in obj.bound_box]),


)


newlink.scale = [max(bound_box)*scale] * 3


else:


newlink.scale = [scale] * 3
if obj.parent is not None and parent_link:
eUtils.parentObjectsTo(newlink, obj.parent)





if parent_objects:


eUtils.parentObjectsTo(obj, newlink)


obj.phobostype = 'visual'


if reparent_children:


eUtils.parentObjectsTo(list(obj.children), newlink)


if bpy.context.scene.phoboswireframesettings.links:


newlink.display_type = "WIRE"





# Add the collection sorting fix


bUtils.sortObjectToCollection(newlink, cname='link')





return newlink


Expand Down
12 changes: 6 additions & 6 deletions phobos/blender/model/poses.py
Original file line number Diff line number Diff line change
Expand Up @@ -123,7 +123,7 @@ def storePose(root, posename):

"""
if not posename:
log("No pose name given", "WARN")
log("No pose name given", "WARNING")
return
if root:
links = sUtils.getChildren(root, ('link',), True, False)
Expand Down Expand Up @@ -159,10 +159,10 @@ def loadPose(modelname, posename):

"""
if not modelname:
log("No model name given", "WARN")
log("No model name given", "WARNING")
return
if not posename:
log("No pose name given", "WARN")
log("No pose name given", "WARNING")
return
root = sUtils.getModelRoot(modelname)
if not root:
Expand Down Expand Up @@ -204,10 +204,10 @@ def deletePose(modelname, posename):

"""
if not modelname:
log("No model name given", "WARN")
log("No model name given", "WARNING")
return
if not posename:
log("No pose name given", "WARN")
log("No pose name given", "WARNING")
return
root = sUtils.getModelRoot(modelname)
if not root:
Expand Down Expand Up @@ -241,7 +241,7 @@ def getPoses(modelname):

"""
if not modelname:
log("No model name given", "WARN")
log("No model name given", "WARNING")
return
root = sUtils.getModelRoot(modelname)
if not root:
Expand Down
30 changes: 21 additions & 9 deletions phobos/blender/operators/editing.py
Original file line number Diff line number Diff line change
Expand Up @@ -1579,13 +1579,13 @@ def invoke(self, context, event):
if "joint/limits/effort" in obj:
self.maxeffort = obj["joint/limits/effort"]
if "joint/limits/velocity" in obj:
self.maxspeed = obj["joint/limits/velocity"]
self.maxvelocity = obj["joint/limits/velocity"]
if "joint/type" in obj:
self.joint_type = obj["joint/type"]
if "joint/axis" in obj:
self.axis = obj["joint/axis"]
self.name = obj.get("joint/name", obj.name)
return self.execute(context)
return context.window_manager.invoke_props_dialog(self)

def execute(self, context):
"""
Expand Down Expand Up @@ -1635,7 +1635,7 @@ def execute(self, context):
for joint in (obj for obj in context.selected_objects if obj.phobostype == 'link'):
context.view_layer.objects.active = joint
if joint.parent is None or joint.parent.phobostype != "link":
ErrorMessageWithBox(f"Link {joint.name} has to be parented to another link before you can define a joint")
self.report({'ERROR'}, f"Link {joint.name} has to be parented to another link before you can define a joint.")
return {'CANCELLED'}
if len(self.name) > 0:
joint["joint/name"] = self.name.replace(" ", "_")
Expand Down Expand Up @@ -2048,6 +2048,14 @@ class CreateLinksOperator(Operator):
name="Link Name", description="A name for a single newly created link.", default='new_link'
)

def invoke(self, context, event):
"""Sets the default location based on whether objects are selected."""
if context.selected_objects:
self.location = 'selected objects'
else:
self.location = '3D cursor'
return context.window_manager.invoke_props_dialog(self)

def execute(self, context):
"""

Expand All @@ -2060,7 +2068,8 @@ def execute(self, context):
if self.location == '3D cursor':
phobos2blender.createLink(representation.Link(name=self.linkname, scale=self.size))
elif len(context.selected_objects) > 0:
objs_to_create_links = context.selected_objects
# Make a true copy of the list, so it's not affected by selection changes
objs_to_create_links = list(context.selected_objects)
for obj in objs_to_create_links:
modellinks.deriveLinkfromObject(obj, scale=self.size, scaleByBoundingBox=self.sizeCheck,
parent_objects=self.parent_objects, parent_link=self.parent_link)
Expand Down Expand Up @@ -2897,7 +2906,12 @@ def execute(self, context):
return {'FINISHED'}


# [TODO v2.0.0] REVIEW this
def get_submodel_types(self, context):
"""Returns a list of submodel types for the EnumProperty."""
return tuple([(sub,) * 3 for sub in defs.definitions['submodeltypes']])


# [TODO v2.2.0] REVIEW this
class DefineSubmodel(Operator):
"""Define a new submodel from objects"""

Expand All @@ -2914,9 +2928,8 @@ class DefineSubmodel(Operator):
)

submodeltype : EnumProperty(
items=tuple([(sub,) * 3 for sub in defs.definitions['submodeltypes']]),
items=get_submodel_types,
name="Submodel type",
default="mechanism",
description="The type for the new submodel",
)

Expand Down Expand Up @@ -3358,8 +3371,7 @@ def execute(self, context):
oldroot = sUtils.getRoot(obj=context.active_object)

if newroot == oldroot:
log("Object is already root.", 'INFO')
return {'CANCELLED'}
log("Object is already root. Re-applying properties to ensure consistency.", 'INFO')

# gather model information from old root
modelprops = eUtils.getProperties(oldroot, category='model')
Expand Down
Loading