shortcuts.py
Go to the documentation of this file.
1 # ruff: noqa: E501
2 #
3 # Copyright (c) 2018-2020 CNRS INRIA
4 #
5 
6 
7 
8 # TODO: Remove when 20.04 is not supported
9 from __future__ import annotations
10 
11 from . import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS
12 from . import pinocchio_pywrap_default as pin
13 
14 nle = pin.nonLinearEffects
15 
16 
18  filename, *args, **kwargs
19 ) -> tuple[pin.Model, pin.GeometryModel, pin.GeometryModel]:
20  """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.
21  Arguments:
22  - filename - name of the urdf file to load
23  - package_dirs - where the meshes of the urdf are located. (default - None)
24  - root_joint - Joint at the base of the model (default - None)
25  - root_joint_name - Name for the root_joint (default - "root_joint")
26  - verbose - print information of parsing (default - False)
27  - meshLoader - object used to load meshes (default - hpp::fcl::MeshLoader)
28  - geometry_types - Which geometry model to load. Can be pin.GeometryType.COLLISION, pin.GeometryType.VISUAL or both. (default - [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL])
29  - mimic - If urdf mimic joints should be parsed or not (default - False)
30  Return:
31  Tuple of the models, in this order : model, collision model, and visual model.
32 
33  Example:
34  model, collision_model, visual_model = buildModelsFromUrdf(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
35 
36  Remark: In the URDF format, a joint of type fixed can be defined. For efficiency reasons, it is treated as operational frame and not as a joint of the model.
37  """
38  # Handle the switch from old to new api
39  arg_keys = [
40  "package_dirs",
41  "root_joint",
42  "verbose",
43  "meshLoader",
44  "geometry_types",
45  "mimic",
46  ]
47  if len(args) >= 3:
48  if isinstance(args[2], str):
49  arg_keys = [
50  "package_dirs",
51  "root_joint",
52  "root_joint_name",
53  "verbose",
54  "meshLoader",
55  "geometry_types",
56  "mimic",
57  ]
58 
59  for key, arg in zip(arg_keys, args):
60  if key in kwargs.keys():
61  raise TypeError("Function got multiple values for argument ", key)
62  else:
63  kwargs[key] = arg
64 
65  return _buildModelsFromUrdf(filename, **kwargs)
66 
67 
69  filename,
70  package_dirs=None,
71  root_joint=None,
72  root_joint_name=None,
73  verbose=False,
74  meshLoader=None,
75  geometry_types=None,
76  mimic=False,
77 ) -> tuple[pin.Model, pin.GeometryModel, pin.GeometryModel]:
78  if geometry_types is None:
79  geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
80 
81  if root_joint is None:
82  model = pin.buildModelFromUrdf(filename, mimic)
83  elif root_joint is not None and root_joint_name is None:
84  model = pin.buildModelFromUrdf(filename, root_joint, mimic)
85  else:
86  model = pin.buildModelFromUrdf(filename, root_joint, root_joint_name, mimic)
87 
88  if verbose and not WITH_HPP_FCL and meshLoader is not None:
89  print(
90  "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
91  )
92  if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
93  print(
94  "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
95  )
96  if package_dirs is None:
97  package_dirs = []
98 
99  lst = [model]
100 
101  if not hasattr(geometry_types, "__iter__"):
102  geometry_types = [geometry_types]
103 
104  for geometry_type in geometry_types:
105  if meshLoader is None or (not WITH_HPP_FCL and not WITH_HPP_FCL_BINDINGS):
106  geom_model = pin.buildGeomFromUrdf(
107  model, filename, geometry_type, package_dirs=package_dirs
108  )
109  else:
110  geom_model = pin.buildGeomFromUrdf(
111  model,
112  filename,
113  geometry_type,
114  package_dirs=package_dirs,
115  mesh_loader=meshLoader,
116  )
117  lst.append(geom_model)
118 
119  return tuple(lst)
120 
121 
122 def createDatas(*models):
123  """
124  Call createData() on each Model or GeometryModel in input and return the results in
125  a tuple. If one of the models is None, the corresponding data object in the result
126  is also None.
127  """
128  return tuple([None if model is None else model.createData() for model in models])
129 
130 
132  filename, *args, **kwargs
133 ) -> tuple[pin.Model, pin.GeometryModel, pin.GeometryModel]:
134  """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.
135  Arguments:
136  - filename - name of the urdf file to load
137  - package_dirs - where the meshes of the urdf are located. (default - None)
138  - root_joint - Joint at the base of the model (default - None)
139  - root_link_name - Name of the body to use as root of the model (default - "")
140  - root_joint_name - Name for the root_joint (default - "root_joint")
141  - parent_guidance - Joint names which should be preferred for cases where two joints can qualify as parent. The other joint appears in the constraint_model. If empty, joint appearance order in .sdf is taken as default.
142  - verbose - print information of parsing (default - False)
143  - meshLoader - object used to load meshes (default - hpp::fcl::MeshLoader)
144  - geometry_types - Which geometry model to load. Can be pin.GeometryType.COLLISION, pin.GeometryType.VISUAL, both or None. (default - None])
145  Return:
146  Tuple of the models, in this order : model, collision model, and visual model.
147 
148  Example:
149  model, collision_model, visual_model = buildModelsFromSdf(filename, root_joint, root_link_name, parent_guidance, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
150  """
151 
152  arg_keys = [
153  "package_dirs",
154  "root_joint",
155  "root_link_name",
156  "parent_guidance",
157  "verbose",
158  "meshLoader",
159  "geometry_types",
160  ]
161  # Handle the switch from old to new api
162  if len(args) >= 4:
163  if isinstance(args[3], str):
164  arg_keys = [
165  "package_dirs",
166  "root_joint",
167  "root_link_name",
168  "root_joint_name",
169  "parent_guidance",
170  "verbose",
171  "meshLoader",
172  "geometry_types",
173  ]
174 
175  for key, arg in zip(arg_keys, args):
176  if key in kwargs.keys():
177  raise TypeError("Function got multiple values for argument ", key)
178  else:
179  kwargs[key] = arg
180 
181  return _buildModelsFromSdf(filename, **kwargs)
182 
183 
185  filename,
186  package_dirs=None,
187  root_joint=None,
188  root_link_name="",
189  root_joint_name=None,
190  parent_guidance=None,
191  verbose=False,
192  meshLoader=None,
193  geometry_types=None,
194 ):
195  if parent_guidance is None:
196  parent_guidance = []
197 
198  if geometry_types is None:
199  geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
200 
201  if root_joint is None:
202  model, constraint_models = pin.buildModelFromSdf(
203  filename, root_link_name, parent_guidance
204  )
205  elif root_joint is not None and root_joint_name is None:
206  model, constraint_models = pin.buildModelFromSdf(
207  filename, root_joint, root_link_name, parent_guidance
208  )
209  else:
210  model, constraint_models = pin.buildModelFromSdf(
211  filename, root_joint, root_link_name, root_joint_name, parent_guidance
212  )
213  if verbose and not WITH_HPP_FCL and meshLoader is not None:
214  print(
215  "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
216  )
217  if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
218  print(
219  "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
220  )
221  if package_dirs is None:
222  package_dirs = []
223 
224  lst = [model, constraint_models]
225 
226  if not hasattr(geometry_types, "__iter__"):
227  geometry_types = [geometry_types]
228 
229  for geometry_type in geometry_types:
230  if meshLoader is None or (not WITH_HPP_FCL and not WITH_HPP_FCL_BINDINGS):
231  geom_model = pin.buildGeomFromSdf(
232  model, filename, geometry_type, root_link_name, package_dirs
233  )
234  else:
235  geom_model = pin.buildGeomFromSdf(
236  model, filename, geometry_type, root_link_name, package_dirs, meshLoader
237  )
238  lst.append(geom_model)
239 
240  return tuple(lst)
241 
242 
243 def buildModelsFromMJCF(filename, *args, **kwargs):
244  """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.
245  Arguments:
246  - filename - name of the urdf file to load
247  - package_dirs - where the meshes of the urdf are located. (default - None)
248  - root_joint - Joint at the base of the model (default - None)
249  - root_joint_name - Name for the root_joint (default - "root_joint")
250  - verbose - print information of parsing (default - False)
251  - meshLoader - object used to load meshes (default - hpp::fcl::MeshLoader)
252  - geometry_types - Which geometry model to load. Can be pin.GeometryType.COLLISION, pin.GeometryType.VISUAL or both. (default - [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL])
253  - contacts - Boolean to know if contraint models are wanted (default - False)
254  Return:
255  Tuple of the models, in this order : model, collision model, and visual model, or model, constraint_list, collision model, and visual model, if contacts is True.
256 
257  Example:
258  model, collision_model, visual_model = buildModelsFromMJCF(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
259  """
260  # Handle the switch from old to new api
261  arg_keys = ["root_joint", "verbose", "meshLoader", "geometry_types", "contacts"]
262  if len(args) >= 2:
263  if isinstance(args[1], str):
264  arg_keys = [
265  "root_joint",
266  "root_joint_name",
267  "verbose",
268  "meshLoader",
269  "geometry_types",
270  "contacts",
271  ]
272 
273  for key, arg in zip(arg_keys, args):
274  if key in kwargs.keys():
275  raise TypeError("Function got multiple values for argument ", key)
276  else:
277  kwargs[key] = arg
278 
279  return _buildModelsFromMJCF(filename, **kwargs)
280 
281 
283  filename,
284  root_joint=None,
285  root_joint_name=None,
286  verbose=False,
287  meshLoader=None,
288  geometry_types=None,
289  contacts=False,
290 ):
291  if geometry_types is None:
292  geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
293 
294  contact_models = []
295  if root_joint is None:
296  model = pin.buildModelFromMJCF(filename)
297  elif root_joint is not None and root_joint_name is None:
298  model = pin.buildModelFromMJCF(filename, root_joint)
299  else:
300  model, contact_models = pin.buildModelFromMJCF(
301  filename, root_joint, root_joint_name
302  )
303 
304  if verbose and not WITH_HPP_FCL and meshLoader is not None:
305  print(
306  "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
307  )
308  if verbose and not WITH_HPP_FCL_BINDINGS and meshLoader is not None:
309  print(
310  "Info: MeshLoader is ignored. "
311  "The HPP-FCL Python bindings have not been installed."
312  )
313 
314  lst = [model]
315  if contacts:
316  lst.append(contact_models)
317 
318  if not hasattr(geometry_types, "__iter__"):
319  geometry_types = [geometry_types]
320 
321  for geometry_type in geometry_types:
322  if meshLoader is None or (not WITH_HPP_FCL and not WITH_HPP_FCL_BINDINGS):
323  geom_model = pin.buildGeomFromMJCF(model, filename, geometry_type)
324  else:
325  geom_model = pin.buildGeomFromMJCF(
326  model, filename, geometry_type, mesh_loader=meshLoader
327  )
328  lst.append(geom_model)
329 
330  return tuple(lst)
pinocchio.shortcuts._buildModelsFromUrdf
tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] _buildModelsFromUrdf(filename, package_dirs=None, root_joint=None, root_joint_name=None, verbose=False, meshLoader=None, geometry_types=None, mimic=False)
Definition: shortcuts.py:68
pinocchio.shortcuts.buildModelsFromUrdf
tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] buildModelsFromUrdf(filename, *args, **kwargs)
Definition: shortcuts.py:17
pinocchio.shortcuts._buildModelsFromMJCF
def _buildModelsFromMJCF(filename, root_joint=None, root_joint_name=None, verbose=False, meshLoader=None, geometry_types=None, contacts=False)
Definition: shortcuts.py:282
pinocchio.shortcuts.createDatas
def createDatas(*models)
Definition: shortcuts.py:122
pinocchio.shortcuts.buildModelsFromSdf
tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] buildModelsFromSdf(filename, *args, **kwargs)
Definition: shortcuts.py:131
pinocchio.shortcuts._buildModelsFromSdf
def _buildModelsFromSdf(filename, package_dirs=None, root_joint=None, root_link_name="", root_joint_name=None, parent_guidance=None, verbose=False, meshLoader=None, geometry_types=None)
Definition: shortcuts.py:184
pinocchio.shortcuts.buildModelsFromMJCF
def buildModelsFromMJCF(filename, *args, **kwargs)
Definition: shortcuts.py:243


pinocchio
Author(s):
autogenerated on Wed Apr 16 2025 02:41:51