shortcuts.py
Go to the documentation of this file.
1 #
2 # Copyright (c) 2018-2020 CNRS INRIA
3 #
4 
5 
6 
7 from . import pinocchio_pywrap as pin
8 from . import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS
9 
10 nle = pin.nonLinearEffects
11 
12 def buildModelsFromUrdf(filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None, geometry_types=[pin.GeometryType.COLLISION,pin.GeometryType.VISUAL]):
13  """Parse the URDF file given in input and return a Pinocchio Model followed by corresponding GeometryModels of types specified by geometry_types, in the same order as listed.
14  Examples of usage:
15  # load model, collision model, and visual model, in this order (default)
16  model, collision_model, visual_model = buildModelsFromUrdf(filename[, ...], geometry_types=[pin.GeometryType.COLLISION,pin.GeometryType.VISUAL])
17  model, collision_model, visual_model = buildModelsFromUrdf(filename[, ...]) # same as above
18 
19  model, collision_model = buildModelsFromUrdf(filename[, ...], geometry_types=[pin.GeometryType.COLLISION]) # only load the model and the collision model
20  model, collision_model = buildModelsFromUrdf(filename[, ...], geometry_types=pin.GeometryType.COLLISION) # same as above
21  model, visual_model = buildModelsFromUrdf(filename[, ...], geometry_types=pin.GeometryType.VISUAL) # only load the model and the visual model
22 
23  model = buildModelsFromUrdf(filename[, ...], geometry_types=[]) # equivalent to buildModelFromUrdf(filename[, root_joint])
24 
25  Remark:
26  Remark: In the URDF format, a joint of type fixed can be defined.
27  For efficiency reasons, it is treated as operational frame and not as a joint of the model.
28  """
29 
30  if root_joint is None:
31  model = pin.buildModelFromUrdf(filename)
32  else:
33  model = pin.buildModelFromUrdf(filename, root_joint)
34 
35  if verbose and not WITH_HPP_FCL and meshLoader is not None:
36  print('Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL.')
37  if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
38  print('Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed.')
39  if package_dirs is None:
40  package_dirs = []
41 
42  lst = [model]
43 
44  if not hasattr(geometry_types, '__iter__'):
45  geometry_types = [geometry_types]
46 
47  for geometry_type in geometry_types:
48  if meshLoader is None or (not WITH_HPP_FCL and not WITH_HPP_FCL_BINDINGS):
49  geom_model = pin.buildGeomFromUrdf(model, filename, geometry_type, package_dirs = package_dirs)
50  else:
51  geom_model = pin.buildGeomFromUrdf(model, filename, geometry_type, package_dirs = package_dirs, mesh_loader = meshLoader)
52  lst.append(geom_model)
53 
54  return tuple(lst)
55 
56 def createDatas(*models):
57  """Call createData() on each Model or GeometryModel in input and return the results in a tuple.
58  If one of the models is None, the corresponding data object in the result is also None.
59  """
60  return tuple([None if model is None else model.createData() for model in models])
def createDatas(models)
Definition: shortcuts.py:56
def buildModelsFromUrdf(filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None, geometry_types=[pin.GeometryType.COLLISION, pin, GeometryType, VISUAL)
Definition: shortcuts.py:12


pinocchio
Author(s):
autogenerated on Fri Jun 23 2023 02:38:32