8 from .
import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS
9 from .
import pinocchio_pywrap_default
as pin
11 nle = pin.nonLinearEffects
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.
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)
28 Tuple of the models, in this order : model, collision model, and visual model.
31 model, collision_model, visual_model = buildModelsFromUrdf(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
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.
45 if isinstance(args[2], str):
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)
74 ) -> tuple[pin.Model, pin.GeometryModel, pin.GeometryModel]:
75 if geometry_types
is None:
76 geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
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)
83 model = pin.buildModelFromUrdf(filename, root_joint, root_joint_name, mimic)
85 if verbose
and not WITH_HPP_FCL
and meshLoader
is not None:
87 "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
89 if verbose
and not WITH_HPP_FCL_BINDINGS
and meshLoader
is not None:
91 "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
93 if package_dirs
is None:
98 if not hasattr(geometry_types,
"__iter__"):
99 geometry_types = [geometry_types]
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
107 geom_model = pin.buildGeomFromUrdf(
111 package_dirs=package_dirs,
112 mesh_loader=meshLoader,
114 lst.append(geom_model)
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
125 return tuple([
None if model
is None else model.createData()
for model
in models])
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.
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])
143 Tuple of the models, in this order : model, collision model, and visual model.
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")
160 if isinstance(args[3], str):
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)
186 root_joint_name=None,
187 parent_guidance=None,
192 if parent_guidance
is None:
195 if geometry_types
is None:
196 geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
198 if root_joint
is None:
199 model, constraint_models = pin.buildModelFromSdf(
200 filename, root_link_name, parent_guidance
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
207 model, constraint_models = pin.buildModelFromSdf(
208 filename, root_joint, root_link_name, root_joint_name, parent_guidance
210 if verbose
and not WITH_HPP_FCL
and meshLoader
is not None:
212 "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
214 if verbose
and not WITH_HPP_FCL_BINDINGS
and meshLoader
is not None:
216 "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
218 if package_dirs
is None:
221 lst = [model, constraint_models]
223 if not hasattr(geometry_types,
"__iter__"):
224 geometry_types = [geometry_types]
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
232 geom_model = pin.buildGeomFromSdf(
233 model, filename, geometry_type, root_link_name, package_dirs, meshLoader
235 lst.append(geom_model)
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.
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)
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.
255 model, collision_model, visual_model = buildModelsFromMJCF(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
258 arg_keys = [
"root_joint",
"verbose",
"meshLoader",
"geometry_types",
"contacts"]
260 if isinstance(args[1], str):
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)
282 root_joint_name=None,
288 if geometry_types
is None:
289 geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
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)
297 model, contact_models = pin.buildModelFromMJCF(
298 filename, root_joint, root_joint_name
301 if verbose
and not WITH_HPP_FCL
and meshLoader
is not None:
303 "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
305 if verbose
and not WITH_HPP_FCL_BINDINGS
and meshLoader
is not None:
307 "Info: MeshLoader is ignored. "
308 "The HPP-FCL Python bindings have not been installed."
313 lst.append(contact_models)
315 if not hasattr(geometry_types,
"__iter__"):
316 geometry_types = [geometry_types]
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)
322 geom_model = pin.buildGeomFromMJCF(
323 model, filename, geometry_type, mesh_loader=meshLoader
325 lst.append(geom_model)