Tool for convert FreeCAD sub-assemblies to URDF-world according to config
This commit is contained in:
parent
03bc34539c
commit
184ac7df88
12 changed files with 327 additions and 119 deletions
4
asp/mocks/urdf/asm.urdf
Normal file
4
asp/mocks/urdf/asm.urdf
Normal file
|
@ -0,0 +1,4 @@
|
||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<robossembler
|
||||||
|
name="{name}">
|
||||||
|
</robossembler>
|
13
asp/mocks/urdf/joint.urdf
Normal file
13
asp/mocks/urdf/joint.urdf
Normal file
|
@ -0,0 +1,13 @@
|
||||||
|
<joint
|
||||||
|
name="{joint_name}"
|
||||||
|
type="{joint_type}">
|
||||||
|
<origin
|
||||||
|
xyz="{joint_location}"
|
||||||
|
rpy="{joint_rotation}" />
|
||||||
|
<parent
|
||||||
|
link="{parent_part}" />
|
||||||
|
<child
|
||||||
|
link="{child_part}" />
|
||||||
|
<axis
|
||||||
|
xyz="0 0 1" />
|
||||||
|
</joint>
|
31
asp/mocks/urdf/link.urdf
Normal file
31
asp/mocks/urdf/link.urdf
Normal file
|
@ -0,0 +1,31 @@
|
||||||
|
<link
|
||||||
|
name="{part_name}">
|
||||||
|
<inertial>
|
||||||
|
<origin
|
||||||
|
xyz="0 0 0"
|
||||||
|
rpy="0 0 0" />
|
||||||
|
<mass
|
||||||
|
value="{mass}" />
|
||||||
|
<inertia
|
||||||
|
ixx="0.0"
|
||||||
|
ixy="0.0"
|
||||||
|
ixz="0.0"
|
||||||
|
iyy="0.0"
|
||||||
|
iyz="0.0"
|
||||||
|
izz="0.0" />
|
||||||
|
</inertial>
|
||||||
|
<visual>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="{visual_file}"
|
||||||
|
scale="1.0 1.0 1.0" />
|
||||||
|
</geometry>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<geometry>
|
||||||
|
<mesh
|
||||||
|
filename="{collision_file}"
|
||||||
|
scale="1.0 1.0 1.0" />
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
|
@ -1,7 +1,52 @@
|
||||||
# -*- coding: utf-8 -*-
|
# -*- coding: utf-8 -*-
|
||||||
"""
|
# Copyright (C) 2023 Ilia Kurochkin <brothermechanic@gmail.com>
|
||||||
|
#
|
||||||
|
# This program is free software; you can redistribute it and/or modify
|
||||||
|
# it under the terms of the GNU General Public License as published by
|
||||||
|
# the Free Software Foundation; either version 3 of the License, or
|
||||||
|
# (at your option) any later version.
|
||||||
|
#
|
||||||
|
# This program 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 General Public License for more details.
|
||||||
|
'''
|
||||||
DESCRIPTION.
|
DESCRIPTION.
|
||||||
Blender export modules.
|
Decorator for export functions.
|
||||||
Modules exports all objests in scene.
|
'''
|
||||||
You can set export path and subdir.
|
import logging
|
||||||
"""
|
import os
|
||||||
|
import bpy
|
||||||
|
import mathutils
|
||||||
|
|
||||||
|
logger = logging.getLogger(__name__)
|
||||||
|
logging.basicConfig(level=logging.INFO)
|
||||||
|
|
||||||
|
|
||||||
|
def export_decorator(func):
|
||||||
|
|
||||||
|
def wrapper(**kwargs):
|
||||||
|
# add defaults
|
||||||
|
kwargs.setdefault('path', '//')
|
||||||
|
kwargs.setdefault('subdir', '')
|
||||||
|
|
||||||
|
obj = bpy.data.objects.get(kwargs['obj_name'])
|
||||||
|
# deselect all but just one object and make it active
|
||||||
|
bpy.ops.object.select_all(action='DESELECT')
|
||||||
|
obj.select_set(state=True)
|
||||||
|
bpy.context.view_layer.objects.active = obj
|
||||||
|
# clean hierarchy and transforms
|
||||||
|
obj.parent = None
|
||||||
|
obj.matrix_world = mathutils.Matrix()
|
||||||
|
# construct path
|
||||||
|
filename = bpy.context.active_object.name
|
||||||
|
filepath = os.path.join(kwargs['path'],
|
||||||
|
kwargs['subdir']).replace('\\', '/')
|
||||||
|
if not os.path.isdir(filepath):
|
||||||
|
os.makedirs(filepath)
|
||||||
|
# store path
|
||||||
|
kwargs['outpath'] = os.path.join(filepath, filename)
|
||||||
|
# return export function
|
||||||
|
return func(**kwargs)
|
||||||
|
|
||||||
|
return wrapper
|
||||||
|
|
|
@ -1,34 +1,64 @@
|
||||||
# -*- coding: utf-8 -*-
|
# -*- coding: utf-8 -*-
|
||||||
"""
|
# Copyright (C) 2023 Ilia Kurochkin <brothermechanic@gmail.com>
|
||||||
|
#
|
||||||
|
# This program is free software; you can redistribute it and/or modify
|
||||||
|
# it under the terms of the GNU General Public License as published by
|
||||||
|
# the Free Software Foundation; either version 3 of the License, or
|
||||||
|
# (at your option) any later version.
|
||||||
|
#
|
||||||
|
# This program 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 General Public License for more details.
|
||||||
|
'''
|
||||||
DESCRIPTION.
|
DESCRIPTION.
|
||||||
Collada mesh exporter.
|
Collada mesh exporter.
|
||||||
Exports all objects in scene.
|
Exports all objects in scene.
|
||||||
You can set export path and subdir.
|
You can set export path and subdir.
|
||||||
"""
|
'''
|
||||||
__version__ = "0.1"
|
__version__ = "0.2"
|
||||||
|
|
||||||
import logging
|
|
||||||
import sys
|
|
||||||
import bpy
|
import bpy
|
||||||
import os
|
from blender.export import export_decorator
|
||||||
|
|
||||||
logger = logging.getLogger(__name__)
|
|
||||||
logging.basicConfig(level=logging.INFO)
|
|
||||||
|
|
||||||
|
|
||||||
def export_dae(path, subdir=""):
|
@export_decorator
|
||||||
""" Collada mesh exporter. Exports all objects in scene. """
|
def export_dae(**kwargs):
|
||||||
for ob in bpy.context.scene.objects:
|
outpath = ('{}.dae'.format(kwargs['outpath']))
|
||||||
# deselect all but just one object and make it active
|
|
||||||
bpy.ops.object.select_all(action='DESELECT')
|
|
||||||
ob.select_set(state=True)
|
|
||||||
bpy.context.view_layer.objects.active = ob
|
|
||||||
filename = bpy.context.active_object.name
|
|
||||||
# export dae
|
|
||||||
dae_path = os.path.join(path, subdir).replace('\\', '/')
|
|
||||||
if not os.path.isdir(dae_path):
|
|
||||||
os.makedirs(dae_path)
|
|
||||||
outpath = os.path.join(dae_path, filename)
|
|
||||||
logger.debug('vizual:', outpath)
|
|
||||||
|
|
||||||
bpy.ops.wm.collada_export(filepath=outpath, check_existing=False, apply_modifiers=True, export_mesh_type=0, export_mesh_type_selection='view', export_global_forward_selection='Y', export_global_up_selection='Z', apply_global_orientation=False, selected=True, include_children=False, include_armatures=False, include_shapekeys=False, deform_bones_only=False, include_animations=False, include_all_actions=True, export_animation_type_selection='sample', sampling_rate=1, keep_smooth_curves=False, keep_keyframes=False, keep_flat_curves=False, active_uv_only=False, use_texture_copies=True, triangulate=True, use_object_instantiation=True, use_blender_profile=True, sort_by_name=False, export_object_transformation_type=0, export_object_transformation_type_selection='matrix', export_animation_transformation_type=0, export_animation_transformation_type_selection='matrix', open_sim=False, limit_precision=False, keep_bind_info=False)
|
bpy.ops.wm.collada_export(
|
||||||
|
filepath=outpath,
|
||||||
|
check_existing=False,
|
||||||
|
apply_modifiers=True,
|
||||||
|
export_mesh_type=0,
|
||||||
|
export_mesh_type_selection='view',
|
||||||
|
export_global_forward_selection='Y',
|
||||||
|
export_global_up_selection='Z',
|
||||||
|
apply_global_orientation=False,
|
||||||
|
selected=True,
|
||||||
|
include_children=False,
|
||||||
|
include_armatures=False,
|
||||||
|
include_shapekeys=False,
|
||||||
|
deform_bones_only=False,
|
||||||
|
include_animations=False,
|
||||||
|
include_all_actions=True,
|
||||||
|
export_animation_type_selection='sample',
|
||||||
|
sampling_rate=1,
|
||||||
|
keep_smooth_curves=False,
|
||||||
|
keep_keyframes=False,
|
||||||
|
keep_flat_curves=False,
|
||||||
|
active_uv_only=False,
|
||||||
|
use_texture_copies=True,
|
||||||
|
triangulate=True,
|
||||||
|
use_object_instantiation=True,
|
||||||
|
use_blender_profile=True,
|
||||||
|
sort_by_name=False,
|
||||||
|
export_object_transformation_type=0,
|
||||||
|
export_object_transformation_type_selection='matrix',
|
||||||
|
export_animation_transformation_type=0,
|
||||||
|
export_animation_transformation_type_selection='matrix',
|
||||||
|
open_sim=False,
|
||||||
|
limit_precision=False,
|
||||||
|
keep_bind_info=False)
|
||||||
|
|
||||||
|
return outpath
|
||||||
|
|
|
@ -1,34 +1,41 @@
|
||||||
# -*- coding: utf-8 -*-
|
# -*- coding: utf-8 -*-
|
||||||
"""
|
# Copyright (C) 2023 Ilia Kurochkin <brothermechanic@gmail.com>
|
||||||
|
#
|
||||||
|
# This program is free software; you can redistribute it and/or modify
|
||||||
|
# it under the terms of the GNU General Public License as published by
|
||||||
|
# the Free Software Foundation; either version 3 of the License, or
|
||||||
|
# (at your option) any later version.
|
||||||
|
#
|
||||||
|
# This program 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 General Public License for more details.
|
||||||
|
'''
|
||||||
DESCRIPTION.
|
DESCRIPTION.
|
||||||
STL mesh exporter.
|
STL mesh exporter.
|
||||||
Exports all objects in scene.
|
Exports all objects in scene.
|
||||||
You can set export path and subdir.
|
You can set export path and subdir.
|
||||||
"""
|
'''
|
||||||
__version__ = "0.1"
|
__version__ = "0.2"
|
||||||
|
|
||||||
import logging
|
|
||||||
import sys
|
|
||||||
import bpy
|
import bpy
|
||||||
import os
|
from blender.export import export_decorator
|
||||||
|
|
||||||
logger = logging.getLogger(__name__)
|
|
||||||
logging.basicConfig(level=logging.INFO)
|
|
||||||
|
|
||||||
|
|
||||||
def export_stl(path, subdir=""):
|
@export_decorator
|
||||||
""" STL mesh exporter. Exports all objects in scene. """
|
def export_stl(**kwargs):
|
||||||
for ob in bpy.context.scene.objects:
|
outpath = ('{}.stl'.format(kwargs['outpath']))
|
||||||
# deselect all but just one object and make it active
|
|
||||||
bpy.ops.object.select_all(action='DESELECT')
|
|
||||||
ob.select_set(state=True)
|
|
||||||
bpy.context.view_layer.objects.active = ob
|
|
||||||
filename = bpy.context.active_object.name
|
|
||||||
# export stl
|
|
||||||
stl_path = os.path.join(path, subdir).replace('\\', '/')
|
|
||||||
if not os.path.isdir(stl_path):
|
|
||||||
os.makedirs(stl_path)
|
|
||||||
outpath = os.path.join(stl_path, filename+'.stl')
|
|
||||||
logger.debug('collision:', outpath)
|
|
||||||
|
|
||||||
bpy.ops.export_mesh.stl(filepath=outpath, check_existing=False, filter_glob='*.stl', use_selection=True, global_scale=1.0, use_scene_unit=False, ascii=False, use_mesh_modifiers=True, batch_mode='OFF', axis_forward='Y', axis_up='Z')
|
bpy.ops.export_mesh.stl(filepath=outpath,
|
||||||
|
check_existing=False,
|
||||||
|
filter_glob='*.stl',
|
||||||
|
use_selection=True,
|
||||||
|
global_scale=1000,
|
||||||
|
use_scene_unit=False,
|
||||||
|
ascii=False,
|
||||||
|
use_mesh_modifiers=True,
|
||||||
|
batch_mode='OFF',
|
||||||
|
axis_forward='Y',
|
||||||
|
axis_up='Z')
|
||||||
|
|
||||||
|
return outpath
|
||||||
|
|
|
@ -1,5 +1,4 @@
|
||||||
# -*- coding: utf-8 -*-
|
# -*- coding: utf-8 -*-
|
||||||
# Original code by (C) 2019 yorikvanhavre <yorik@uncreated.net>
|
|
||||||
# Copyright (C) 2023 Ilia Kurochkin <brothermechanic@gmail.com>
|
# Copyright (C) 2023 Ilia Kurochkin <brothermechanic@gmail.com>
|
||||||
#
|
#
|
||||||
# This program is free software; you can redistribute it and/or modify
|
# This program is free software; you can redistribute it and/or modify
|
||||||
|
@ -21,6 +20,7 @@ DESCRIPTION.
|
||||||
'''
|
'''
|
||||||
__version__ = '0.1'
|
__version__ = '0.1'
|
||||||
|
|
||||||
|
import collections
|
||||||
import logging
|
import logging
|
||||||
import random
|
import random
|
||||||
import bpy
|
import bpy
|
||||||
|
@ -66,8 +66,7 @@ def json_to_blend(js_data):
|
||||||
|
|
||||||
fc_file = list(js_data.keys())[0]
|
fc_file = list(js_data.keys())[0]
|
||||||
|
|
||||||
bobjs = []
|
imported_objects = collections.defaultdict(list)
|
||||||
bobjs_for_render = []
|
|
||||||
|
|
||||||
for js_obj in js_data[fc_file]:
|
for js_obj in js_data[fc_file]:
|
||||||
bobj = None
|
bobj = None
|
||||||
|
@ -78,6 +77,7 @@ def json_to_blend(js_data):
|
||||||
bobj.empty_display_size = round(random.uniform(0.05, 0.15), 3)
|
bobj.empty_display_size = round(random.uniform(0.05, 0.15), 3)
|
||||||
bobj.show_in_front = True
|
bobj.show_in_front = True
|
||||||
lcs_collection.objects.link(bobj)
|
lcs_collection.objects.link(bobj)
|
||||||
|
imported_objects['objs_lcs'].append(bobj.name)
|
||||||
|
|
||||||
elif js_data[fc_file][js_obj]['type'] == 'PART':
|
elif js_data[fc_file][js_obj]['type'] == 'PART':
|
||||||
if js_data[fc_file][js_obj].get('mesh'):
|
if js_data[fc_file][js_obj].get('mesh'):
|
||||||
|
@ -107,24 +107,26 @@ def json_to_blend(js_data):
|
||||||
scene_scale)
|
scene_scale)
|
||||||
for hierarchy_obj in hierarchy_objs:
|
for hierarchy_obj in hierarchy_objs:
|
||||||
hierarchy_collection.objects.link(hierarchy_obj)
|
hierarchy_collection.objects.link(hierarchy_obj)
|
||||||
|
imported_objects['objs_hierarchy'].append(hierarchy_obj.name)
|
||||||
|
|
||||||
# one material for the whole object
|
# one material for the whole object
|
||||||
if bobj.type == 'MESH':
|
if bobj.type == 'MESH':
|
||||||
if js_data[fc_file][js_obj].get('material'):
|
if js_data[fc_file][js_obj].get('material'):
|
||||||
fem_mat = js_data[fc_file][js_obj]['material']
|
fem_mat = js_data[fc_file][js_obj]['material']
|
||||||
assign_materials(bobj, fem_mat)
|
assign_materials(bobj, fem_mat)
|
||||||
bobjs_for_render.append(bobj)
|
imported_objects['objs_foreground'].append(bobj.name)
|
||||||
else:
|
else:
|
||||||
assign_black(bobj)
|
assign_black(bobj)
|
||||||
|
imported_objects['objs_background'].append(bobj.name)
|
||||||
bobjs.append(bobj)
|
|
||||||
|
|
||||||
# losted root lcs inlet workaround
|
# losted root lcs inlet workaround
|
||||||
lcs_objects = lcs_collection.objects
|
if imported_objects['objs_lcs']:
|
||||||
if lcs_objects:
|
root_lcs = None
|
||||||
root_lcs = [lcs for lcs in lcs_objects if lcs.name.endswith(root)]
|
for obj_name in imported_objects['objs_lcs']:
|
||||||
|
if obj_name.endswith(root):
|
||||||
|
root_lcs = bpy.data.objects[obj_name]
|
||||||
|
break
|
||||||
if root_lcs:
|
if root_lcs:
|
||||||
root_lcs = root_lcs[0]
|
|
||||||
root_inlet_name = '{}{}'.format(root_lcs.name.split(root)[0], inlet)
|
root_inlet_name = '{}{}'.format(root_lcs.name.split(root)[0], inlet)
|
||||||
if not bpy.data.objects.get(root_inlet_name):
|
if not bpy.data.objects.get(root_inlet_name):
|
||||||
root_inlet = bpy.data.objects.new(root_inlet_name, None)
|
root_inlet = bpy.data.objects.new(root_inlet_name, None)
|
||||||
|
@ -135,10 +137,17 @@ def json_to_blend(js_data):
|
||||||
root_inlet.rotation_euler = root_lcs.rotation_euler
|
root_inlet.rotation_euler = root_lcs.rotation_euler
|
||||||
root_inlet.parent = root_lcs.parent
|
root_inlet.parent = root_lcs.parent
|
||||||
lcs_collection.objects.link(root_inlet)
|
lcs_collection.objects.link(root_inlet)
|
||||||
|
imported_objects['objs_lcs'].append(root_inlet.name)
|
||||||
|
logger.info('Root Inlet LCS object created!')
|
||||||
|
else:
|
||||||
|
logger.info('Root Inlet LCS object already exists!')
|
||||||
else:
|
else:
|
||||||
logger.info('Lost root LCS object!')
|
logger.info('Lost Root LCS object!')
|
||||||
|
else:
|
||||||
|
logger.info('No LCS objects found!')
|
||||||
|
|
||||||
# TODO
|
# TODO
|
||||||
# update do not dork
|
# update do not dork
|
||||||
logger.info('Generated %s objects without errors', len(bobjs))
|
logger.info('Generated %s objects without errors',
|
||||||
return bobjs_for_render
|
len(sum(list(imported_objects.values()), [])))
|
||||||
|
return imported_objects
|
||||||
|
|
|
@ -24,15 +24,16 @@ logger = logging.getLogger(__name__)
|
||||||
logging.basicConfig(level=logging.INFO)
|
logging.basicConfig(level=logging.INFO)
|
||||||
|
|
||||||
|
|
||||||
def setup_meshes(bobjs, cleanup=False, sharpness=False, shading=False):
|
def setup_meshes(obj_names, cleanup=False, sharpness=False, shading=False):
|
||||||
''' Setup raw meshes list after importing '''
|
''' Setup raw meshes list after importing '''
|
||||||
logger.info('Hightpoly meshes setup launched...')
|
logger.info('Hightpoly meshes setup launched...')
|
||||||
for bobj in bobjs:
|
for obj_name in obj_names:
|
||||||
if not bobj.type == 'MESH':
|
obj = bpy.data.objects[obj_name]
|
||||||
|
if not obj.type == 'MESH':
|
||||||
continue
|
continue
|
||||||
bpy.ops.object.select_all(action='DESELECT')
|
bpy.ops.object.select_all(action='DESELECT')
|
||||||
bobj.select_set(state=True)
|
obj.select_set(state=True)
|
||||||
bpy.context.view_layer.objects.active = bobj
|
bpy.context.view_layer.objects.active = obj
|
||||||
|
|
||||||
if cleanup:
|
if cleanup:
|
||||||
# remove doubles
|
# remove doubles
|
||||||
|
@ -68,4 +69,4 @@ def setup_meshes(bobjs, cleanup=False, sharpness=False, shading=False):
|
||||||
bpy.context.object.modifiers['triangulate'].keep_custom_normals = 1
|
bpy.context.object.modifiers['triangulate'].keep_custom_normals = 1
|
||||||
bpy.context.object.modifiers['triangulate'].show_expanded = 0
|
bpy.context.object.modifiers['triangulate'].show_expanded = 0
|
||||||
|
|
||||||
return logger.info('Hightpoly meshes setup finished!')
|
return logger.info('Setup of %s hightpoly meshes is finished!', len(obj_names))
|
||||||
|
|
|
@ -135,6 +135,6 @@ def parts_to_shells(hightpoly_part_names):
|
||||||
bpy.ops.mesh.select_mode(type='FACE')
|
bpy.ops.mesh.select_mode(type='FACE')
|
||||||
bpy.ops.object.mode_set(mode='OBJECT')
|
bpy.ops.object.mode_set(mode='OBJECT')
|
||||||
|
|
||||||
logger.info('Lowpoly shells created successfully!')
|
logger.info('Generation of %s lowpoly shells is finished!', len(lowpoly_col.objects))
|
||||||
|
|
||||||
return lowpoly_col.objects
|
return [obj.name for obj in lowpoly_col.objects]
|
||||||
|
|
|
@ -131,28 +131,42 @@ def lcs_collections(root_lcs, lcs_objects):
|
||||||
return root_lcs.children
|
return root_lcs.children
|
||||||
|
|
||||||
|
|
||||||
def restruct_hierarchy():
|
def restruct_hierarchy(lcs_names):
|
||||||
''' Execute restructurisation. '''
|
''' Execute restructurisation. '''
|
||||||
|
|
||||||
lcs_objects = bpy.data.collections[lcs_col_name].objects
|
#lcs_objects = bpy.data.collections[lcs_col_name].objects
|
||||||
|
lcs_objects = []
|
||||||
|
root_lcs = None
|
||||||
|
if lcs_names:
|
||||||
|
for obj_name in lcs_names:
|
||||||
|
if obj_name.endswith(root):
|
||||||
|
root_lcs = bpy.data.objects[obj_name]
|
||||||
|
lcs_objects.append(bpy.data.objects[obj_name])
|
||||||
|
|
||||||
main_locator = [obj for obj in bpy.data.objects if not obj.parent][0]
|
main_locators = [obj for obj in bpy.data.objects if not obj.parent]
|
||||||
root_lcs = [lcs for lcs in lcs_objects if lcs.name.endswith(root)][0]
|
if len(main_locators) > 1:
|
||||||
lcs_objects = [lcs for lcs in lcs_objects if lcs != root_lcs]
|
logger.info('Scene has several main (root) locators! '
|
||||||
root_locator = root_lcs.parent
|
'This may cause an error!')
|
||||||
unparenting(root_lcs)
|
|
||||||
round_transforms(root_lcs)
|
|
||||||
unparenting(root_locator)
|
|
||||||
parenting(root_lcs, root_locator)
|
|
||||||
parenting(root_lcs, main_locator)
|
|
||||||
|
|
||||||
retree_by_lcs(lcs_objects, root_lcs)
|
if root_lcs:
|
||||||
lcs_constrainting(lcs_objects, root_lcs)
|
lcs_objects = [lcs for lcs in lcs_objects if lcs != root_lcs]
|
||||||
|
root_locator = root_lcs.parent
|
||||||
|
unparenting(root_lcs)
|
||||||
|
round_transforms(root_lcs)
|
||||||
|
unparenting(root_locator)
|
||||||
|
parenting(root_lcs, root_locator)
|
||||||
|
parenting(root_lcs, main_locators[0])
|
||||||
|
|
||||||
lcs_collections(root_lcs, lcs_objects)
|
retree_by_lcs(lcs_objects, root_lcs)
|
||||||
|
lcs_constrainting(lcs_objects, root_lcs)
|
||||||
|
|
||||||
# remove unused for now collection
|
lcs_collections(root_lcs, lcs_objects)
|
||||||
bpy.data.collections.remove(bpy.data.collections[hierarchy_col_name])
|
|
||||||
|
|
||||||
logger.info('Restructuring pipeline finished!')
|
# remove unused for now collection
|
||||||
return lcs_objects
|
bpy.data.collections.remove(bpy.data.collections[hierarchy_col_name])
|
||||||
|
|
||||||
|
return logger.info('Restructuring pipeline finished!')
|
||||||
|
else:
|
||||||
|
return logger.info('Lost root LCS object!')
|
||||||
|
else:
|
||||||
|
return logger.info('Restructuring pipeline canceled!')
|
||||||
|
|
|
@ -24,9 +24,10 @@ logger = logging.getLogger(__name__)
|
||||||
logging.basicConfig(level=logging.INFO)
|
logging.basicConfig(level=logging.INFO)
|
||||||
|
|
||||||
|
|
||||||
def uv_unwrap(objs, angle_limit=30):
|
def uv_unwrap(obj_names, angle_limit=30):
|
||||||
''' UV unwrapping and UV packing processing '''
|
''' UV unwrapping and UV packing processing '''
|
||||||
for obj in objs:
|
for obj_name in obj_names:
|
||||||
|
obj = bpy.data.objects[obj_name]
|
||||||
obj.select_set(True)
|
obj.select_set(True)
|
||||||
bpy.context.view_layer.objects.active = obj
|
bpy.context.view_layer.objects.active = obj
|
||||||
bpy.ops.object.mode_set(mode='EDIT')
|
bpy.ops.object.mode_set(mode='EDIT')
|
||||||
|
@ -60,5 +61,5 @@ def uv_unwrap(objs, angle_limit=30):
|
||||||
bpy.ops.object.mode_set(mode='OBJECT')
|
bpy.ops.object.mode_set(mode='OBJECT')
|
||||||
obj.select_set(False)
|
obj.select_set(False)
|
||||||
|
|
||||||
logger.info('UV unwrapping and UV packing processing done successfully!')
|
return logger.info('UV setup of %s lowpoly meshes is finished!', len(obj_names))
|
||||||
return objs
|
|
||||||
|
|
|
@ -6,9 +6,11 @@ Convert and setup FreeCAD solid objects to 3d assets.
|
||||||
Support Blender compiled as a Python Module only!
|
Support Blender compiled as a Python Module only!
|
||||||
'''
|
'''
|
||||||
__version__ = '0.6'
|
__version__ = '0.6'
|
||||||
|
import collections
|
||||||
import json
|
import json
|
||||||
import logging
|
import logging
|
||||||
import os
|
import os
|
||||||
|
from itertools import zip_longest
|
||||||
|
|
||||||
from blender.utils.remove_collections import remove_collections
|
from blender.utils.remove_collections import remove_collections
|
||||||
from blender.utils.cleanup_orphan_data import cleanup_orphan_data
|
from blender.utils.cleanup_orphan_data import cleanup_orphan_data
|
||||||
|
@ -18,10 +20,10 @@ from blender.processing.restruct_hierarchy_by_lcs import restruct_hierarchy
|
||||||
from blender.processing.highpoly_setup import setup_meshes
|
from blender.processing.highpoly_setup import setup_meshes
|
||||||
from blender.processing.lowpoly_setup import parts_to_shells
|
from blender.processing.lowpoly_setup import parts_to_shells
|
||||||
from blender.processing.uv_setup import uv_unwrap
|
from blender.processing.uv_setup import uv_unwrap
|
||||||
|
from blender.export.dae import export_dae
|
||||||
|
from blender.export.stl import export_stl
|
||||||
import bpy
|
import bpy
|
||||||
import mathutils
|
import mathutils
|
||||||
# from export.dae import export_dae
|
|
||||||
# from export.collision import export_col_stl
|
|
||||||
|
|
||||||
logger = logging.getLogger(__name__)
|
logger = logging.getLogger(__name__)
|
||||||
logging.basicConfig(level=logging.INFO)
|
logging.basicConfig(level=logging.INFO)
|
||||||
|
@ -64,12 +66,15 @@ render = '_render'
|
||||||
def cg_pipeline(**kwargs):
|
def cg_pipeline(**kwargs):
|
||||||
''' CG asset creation pipeline '''
|
''' CG asset creation pipeline '''
|
||||||
|
|
||||||
|
blend_path = kwargs.pop('blend_path', None)
|
||||||
|
mesh_export_path = kwargs.pop('mesh_export_path', None)
|
||||||
|
|
||||||
# prepare blend file
|
# prepare blend file
|
||||||
remove_collections()
|
remove_collections()
|
||||||
cleanup_orphan_data()
|
cleanup_orphan_data()
|
||||||
|
|
||||||
# convert FreeCAD scene to Blender scene
|
# convert FreeCAD scene to Blender scene
|
||||||
objs_for_render = json_to_blend(
|
imported_objects = json_to_blend(
|
||||||
json.loads(
|
json.loads(
|
||||||
cmd_proc(freecadcmd,
|
cmd_proc(freecadcmd,
|
||||||
fcstd_data_script,
|
fcstd_data_script,
|
||||||
|
@ -80,36 +85,84 @@ def cg_pipeline(**kwargs):
|
||||||
)
|
)
|
||||||
|
|
||||||
# restructuring hierarchy by lcs points
|
# restructuring hierarchy by lcs points
|
||||||
lcs_objects = restruct_hierarchy()
|
if imported_objects['objs_lcs']:
|
||||||
|
restruct_hierarchy(imported_objects['objs_lcs'])
|
||||||
|
|
||||||
# save blender scene
|
# save blender scene
|
||||||
if kwargs['blend_path'] is not None:
|
if blend_path is not None:
|
||||||
if not os.path.isdir(os.path.dirname(kwargs['blend_path'])):
|
if not os.path.isdir(os.path.dirname(blend_path)):
|
||||||
os.makedirs(os.path.dirname(kwargs['blend_path']))
|
os.makedirs(os.path.dirname(blend_path))
|
||||||
bpy.ops.wm.save_as_mainfile(filepath=kwargs['blend_path'])
|
bpy.ops.wm.save_as_mainfile(filepath=blend_path)
|
||||||
|
|
||||||
# prepare highpoly
|
# prepare highpoly
|
||||||
setup_meshes(objs_for_render, sharpness=True, shading=True)
|
if imported_objects['objs_foreground']:
|
||||||
|
setup_meshes(imported_objects['objs_foreground'], sharpness=True, shading=True)
|
||||||
|
else:
|
||||||
|
setup_meshes(imported_objects['objs_background'], sharpness=True, shading=True)
|
||||||
|
|
||||||
|
# TODO Part's names from LCS names?
|
||||||
|
part_names = [lcs_name.split(inlet)[0]
|
||||||
|
for lcs_name in imported_objects['objs_lcs']
|
||||||
|
if lcs_name.endswith(inlet)]
|
||||||
|
|
||||||
# prepare lowpoly
|
# prepare lowpoly
|
||||||
part_names = [p.name.split(inlet)[0] for p in lcs_objects if p.name.endswith(inlet)]
|
|
||||||
lowpoly_objs = parts_to_shells(part_names)
|
lowpoly_objs = parts_to_shells(part_names)
|
||||||
uv_unwrap(lowpoly_objs)
|
uv_unwrap(lowpoly_objs)
|
||||||
|
|
||||||
# save blender scene
|
# save blender scene
|
||||||
if kwargs['blend_path'] is not None:
|
if blend_path is not None:
|
||||||
if not os.path.isdir(os.path.dirname(kwargs['blend_path'])):
|
if not os.path.isdir(os.path.dirname(blend_path)):
|
||||||
os.makedirs(os.path.dirname(kwargs['blend_path']))
|
os.makedirs(os.path.dirname(blend_path))
|
||||||
bpy.ops.wm.save_as_mainfile(filepath=kwargs['blend_path'])
|
bpy.ops.wm.save_as_mainfile(filepath=blend_path)
|
||||||
|
|
||||||
# export all objects
|
# export object meshes and urdf
|
||||||
if kwargs['mesh_export_path'] is not None:
|
to_urdf = collections.defaultdict(list)
|
||||||
obs = bpy.context.selected_objects
|
|
||||||
for ob in obs:
|
if lowpoly_objs:
|
||||||
ob.matrix_world = mathutils.Matrix()
|
export_objs = lowpoly_objs
|
||||||
for ob in obs:
|
else:
|
||||||
ob.select_set(state=True)
|
export_objs = sum([imported_objects['objs_foreground'],
|
||||||
export_dae(kwargs['mesh_export_path'])
|
imported_objects['objs_background']], [])
|
||||||
export_col_stl(kwargs['mesh_export_path'])
|
|
||||||
|
link = {}
|
||||||
|
for export_obj in export_objs:
|
||||||
|
link_prop = {}
|
||||||
|
if mesh_export_path is not None:
|
||||||
|
link_prop['visual'] = export_dae(
|
||||||
|
obj_name=export_obj, path=mesh_export_path, subdir='visual')
|
||||||
|
link_prop['collision'] = export_stl(
|
||||||
|
obj_name=export_obj, path=mesh_export_path, subdir='collision')
|
||||||
|
|
||||||
|
link[export_obj] = link_prop
|
||||||
|
|
||||||
|
to_urdf['links'].append(link)
|
||||||
|
|
||||||
|
config = {'sequences': [['cube1', 'cube2', 'cube3', 'cube4'], ['cube2', 'cube1', 'cube4', 'cube3']]}
|
||||||
|
if config:
|
||||||
|
for sequence in config['sequences']:
|
||||||
|
joint = {}
|
||||||
|
for pair in zip_longest(sequence[0::2], sequence[1::2]):
|
||||||
|
joint_prop = {}
|
||||||
|
if pair[1]:
|
||||||
|
joint_prop['type'] = 'fixed'
|
||||||
|
location = list(bpy.data.objects.get(pair[1]).location)
|
||||||
|
rotation = list(bpy.data.objects.get(pair[0]).rotation_euler)
|
||||||
|
# origin
|
||||||
|
# round location values
|
||||||
|
for idx, axis in enumerate(location):
|
||||||
|
location[idx] = round(axis, 5)
|
||||||
|
joint_prop['location'] = location
|
||||||
|
joint_prop['rotation'] = rotation
|
||||||
|
# parent
|
||||||
|
joint_prop['parent'] = pair[0]
|
||||||
|
# child
|
||||||
|
joint_prop['child'] = pair[1]
|
||||||
|
|
||||||
|
joint['_'.join(pair)] = joint_prop
|
||||||
|
|
||||||
|
to_urdf['sequence'].append(joint)
|
||||||
|
|
||||||
|
print(json.dumps(to_urdf, indent=4))
|
||||||
|
|
||||||
|
|
||||||
if __name__ == '__main__':
|
if __name__ == '__main__':
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue