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


pinocchio
Author(s):
autogenerated on Wed May 28 2025 02:41:22