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_default as pin
8 from . import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS
9 from typing import Tuple
10 
11 nle = pin.nonLinearEffects
12 
13 
15  filename,
16  package_dirs=None,
17  root_joint=None,
18  verbose=False,
19  meshLoader=None,
20  geometry_types=[pin.GeometryType.COLLISION, pin.GeometryType.VISUAL],
21 ) -> Tuple[pin.Model, pin.GeometryModel, pin.GeometryModel]:
22  """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.
23  Examples of usage:
24  # load model, collision model, and visual model, in this order (default)
25  model, collision_model, visual_model = buildModelsFromUrdf(filename[, ...], geometry_types=[pin.GeometryType.COLLISION,pin.GeometryType.VISUAL])
26  model, collision_model, visual_model = buildModelsFromUrdf(filename[, ...]) # same as above
27 
28  model, collision_model = buildModelsFromUrdf(filename[, ...], geometry_types=[pin.GeometryType.COLLISION]) # only load the model and the collision model
29  model, collision_model = buildModelsFromUrdf(filename[, ...], geometry_types=pin.GeometryType.COLLISION) # same as above
30  model, visual_model = buildModelsFromUrdf(filename[, ...], geometry_types=pin.GeometryType.VISUAL) # only load the model and the visual model
31 
32  model = buildModelsFromUrdf(filename[, ...], geometry_types=[]) # equivalent to buildModelFromUrdf(filename[, root_joint])
33 
34  Remark:
35  Remark: In the URDF format, a joint of type fixed can be defined.
36  For efficiency reasons, it is treated as operational frame and not as a joint of the model.
37  """
38  if geometry_types is None:
39  geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
40  if root_joint is None:
41  model = pin.buildModelFromUrdf(filename)
42  else:
43  model = pin.buildModelFromUrdf(filename, root_joint)
44 
45  if verbose and not WITH_HPP_FCL and meshLoader is not None:
46  print(
47  "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
48  )
49  if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
50  print(
51  "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
52  )
53  if package_dirs is None:
54  package_dirs = []
55 
56  lst = [model]
57 
58  if not hasattr(geometry_types, "__iter__"):
59  geometry_types = [geometry_types]
60 
61  for geometry_type in geometry_types:
62  if meshLoader is None or (not WITH_HPP_FCL and not WITH_HPP_FCL_BINDINGS):
63  geom_model = pin.buildGeomFromUrdf(
64  model, filename, geometry_type, package_dirs=package_dirs
65  )
66  else:
67  geom_model = pin.buildGeomFromUrdf(
68  model,
69  filename,
70  geometry_type,
71  package_dirs=package_dirs,
72  mesh_loader=meshLoader,
73  )
74  lst.append(geom_model)
75 
76  return tuple(lst)
77 
78 
79 def createDatas(*models):
80  """Call createData() on each Model or GeometryModel in input and return the results in a tuple.
81  If one of the models is None, the corresponding data object in the result is also None.
82  """
83  return tuple([None if model is None else model.createData() for model in models])
84 
85 
87  filename,
88  package_dirs=None,
89  root_joint=None,
90  root_link_name="",
91  parent_guidance=[],
92  verbose=False,
93  meshLoader=None,
94  geometry_types=None,
95 ):
96  """Parse the SDF file given in input and return a Pinocchio Model and a list of Constraint Models, followed by corresponding GeometryModels of types specified by geometry_types, in the same order as listed.
97  Examples of usage:
98  # load model, constraint models, collision model, and visual model, in this order (default)
99  model, constraint_models, collision_model, visual_model = buildModelsFromSdf(filename[, ...], geometry_types=[pin.GeometryType.COLLISION,pin.GeometryType.VISUAL])
100  model, constraint_models, collision_model, visual_model = buildModelsFromSdf(filename[, ...]) # same as above
101  model, constraint_models, collision_model = buildModelsFromSdf(filename[, ...], geometry_types=[pin.GeometryType.COLLISION]) # only load the model, constraint models and the collision model
102  model, constraint_models, collision_model = buildModelsFromSdf(filename[, ...], geometry_types=pin.GeometryType.COLLISION) # same as above
103  model, constraint_models, visual_model = buildModelsFromSdf(filename[, ...], geometry_types=pin.GeometryType.VISUAL) # only load the model and the visual model
104  model, constraint_models = buildModelsFromSdf(filename[, ...], geometry_types=[]) # equivalent to buildModelFromSdf(filename[, root_joint])
105  """
106  if geometry_types is None:
107  geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
108  if root_joint is None:
109  model, constraint_models = pin.buildModelFromSdf(
110  filename, root_link_name, parent_guidance
111  )
112  else:
113  model, constraint_models = pin.buildModelFromSdf(
114  filename, root_joint, root_link_name, parent_guidance
115  )
116 
117  if verbose and not WITH_HPP_FCL and meshLoader is not None:
118  print(
119  "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
120  )
121  if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
122  print(
123  "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
124  )
125  if package_dirs is None:
126  package_dirs = []
127 
128  lst = [model, constraint_models]
129 
130  if not hasattr(geometry_types, "__iter__"):
131  geometry_types = [geometry_types]
132 
133  for geometry_type in geometry_types:
134  if meshLoader is None or (not WITH_HPP_FCL and not WITH_HPP_FCL_BINDINGS):
135  geom_model = pin.buildGeomFromSdf(
136  model, filename, geometry_type, root_link_name, package_dirs
137  )
138  else:
139  geom_model = pin.buildGeomFromSdf(
140  model, filename, geometry_type, root_link_name, package_dirs, meshLoader
141  )
142  lst.append(geom_model)
143 
144  return tuple(lst)
145 
146 
148  filename, root_joint=None, verbose=False, meshLoader=None, geometry_types=None
149 ):
150  """Parse the Mjcf 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.
151  Examples of usage:
152  # load model, constraint models, collision model, and visual model, in this order (default)
153  # load model, collision model, and visual model, in this order (default)
154  model, collision_model, visual_model = buildModelsFromMJCF(filename[, ...], geometry_types=[pin.GeometryType.COLLISION,pin.GeometryType.VISUAL])
155  model, collision_model, visual_model = buildModelsFromMJCF(filename[, ...]) # same as above
156 
157  model, collision_model = buildModelsFromMJCF(filename[, ...], geometry_types=[pin.GeometryType.COLLISION]) # only load the model and the collision model
158  model, collision_model = buildModelsFromMJCF(filename[, ...], geometry_types=pin.GeometryType.COLLISION) # same as above
159  model, visual_model = buildModelsFromMJCF(filename[, ...], geometry_types=pin.GeometryType.VISUAL) # only load the model and the visual model
160 
161  model = buildModelsFromMJCF(filename[, ...], geometry_types=[]) # equivalent to buildModelFromMJCF(filename[, root_joint])
162  """
163  if geometry_types is None:
164  geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
165  if root_joint is None:
166  model = pin.buildModelFromMJCF(filename)
167  else:
168  model = pin.buildModelFromMJCF(filename, root_joint)
169 
170  if verbose and not WITH_HPP_FCL and meshLoader is not None:
171  print(
172  "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
173  )
174  if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
175  print(
176  "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
177  )
178 
179  lst = [model]
180 
181  if not hasattr(geometry_types, "__iter__"):
182  geometry_types = [geometry_types]
183 
184  for geometry_type in geometry_types:
185  if meshLoader is None or (not WITH_HPP_FCL and not WITH_HPP_FCL_BINDINGS):
186  geom_model = pin.buildGeomFromMJCF(model, filename, geometry_type)
187  else:
188  geom_model = pin.buildGeomFromMJCF(
189  model, filename, geometry_type, mesh_loader=meshLoader
190  )
191  lst.append(geom_model)
192 
193  return tuple(lst)
pinocchio.shortcuts.buildModelsFromUrdf
Tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] buildModelsFromUrdf(filename, package_dirs=None, root_joint=None, verbose=False, meshLoader=None, geometry_types=[pin.GeometryType.COLLISION, pin.GeometryType.VISUAL])
Definition: shortcuts.py:14
pinocchio.shortcuts.createDatas
def createDatas(*models)
Definition: shortcuts.py:79
pinocchio.shortcuts.buildModelsFromMJCF
def buildModelsFromMJCF(filename, root_joint=None, verbose=False, meshLoader=None, geometry_types=None)
Definition: shortcuts.py:147
pinocchio.shortcuts.buildModelsFromSdf
def buildModelsFromSdf(filename, package_dirs=None, root_joint=None, root_link_name="", parent_guidance=[], verbose=False, meshLoader=None, geometry_types=None)
Definition: shortcuts.py:86


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:40