9 from __future__
import annotations
11 from .
import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS
12 from .
import pinocchio_pywrap_default
as pin
14 nle = pin.nonLinearEffects
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.
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)
31 Tuple of the models, in this order : model, collision model, and visual model.
34 model, collision_model, visual_model = buildModelsFromUrdf(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
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.
48 if isinstance(args[2], str):
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)
77 ) -> tuple[pin.Model, pin.GeometryModel, pin.GeometryModel]:
78 if geometry_types
is None:
79 geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
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)
86 model = pin.buildModelFromUrdf(filename, root_joint, root_joint_name, mimic)
88 if verbose
and not WITH_HPP_FCL
and meshLoader
is not None:
90 "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
92 if verbose
and not WITH_HPP_FCL_BINDINGS
and meshLoader
is not None:
94 "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
96 if package_dirs
is None:
101 if not hasattr(geometry_types,
"__iter__"):
102 geometry_types = [geometry_types]
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
110 geom_model = pin.buildGeomFromUrdf(
114 package_dirs=package_dirs,
115 mesh_loader=meshLoader,
117 lst.append(geom_model)
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
128 return tuple([
None if model
is None else model.createData()
for model
in models])
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.
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])
146 Tuple of the models, in this order : model, collision model, and visual model.
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")
163 if isinstance(args[3], str):
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)
189 root_joint_name=None,
190 parent_guidance=None,
195 if parent_guidance
is None:
198 if geometry_types
is None:
199 geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
201 if root_joint
is None:
202 model, constraint_models = pin.buildModelFromSdf(
203 filename, root_link_name, parent_guidance
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
210 model, constraint_models = pin.buildModelFromSdf(
211 filename, root_joint, root_link_name, root_joint_name, parent_guidance
213 if verbose
and not WITH_HPP_FCL
and meshLoader
is not None:
215 "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
217 if verbose
and not WITH_HPP_FCL_BINDINGS
and meshLoader
is not None:
219 "Info: MeshLoader is ignored. The HPP-FCL Python bindings have not been installed."
221 if package_dirs
is None:
224 lst = [model, constraint_models]
226 if not hasattr(geometry_types,
"__iter__"):
227 geometry_types = [geometry_types]
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
235 geom_model = pin.buildGeomFromSdf(
236 model, filename, geometry_type, root_link_name, package_dirs, meshLoader
238 lst.append(geom_model)
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.
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)
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.
258 model, collision_model, visual_model = buildModelsFromMJCF(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
261 arg_keys = [
"root_joint",
"verbose",
"meshLoader",
"geometry_types",
"contacts"]
263 if isinstance(args[1], str):
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)
285 root_joint_name=None,
291 if geometry_types
is None:
292 geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]
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)
300 model, contact_models = pin.buildModelFromMJCF(
301 filename, root_joint, root_joint_name
304 if verbose
and not WITH_HPP_FCL
and meshLoader
is not None:
306 "Info: MeshLoader is ignored. Pinocchio has not been compiled with HPP-FCL."
308 if verbose
and not WITH_HPP_FCL_BINDINGS
and meshLoader
is not None:
310 "Info: MeshLoader is ignored. "
311 "The HPP-FCL Python bindings have not been installed."
316 lst.append(contact_models)
318 if not hasattr(geometry_types,
"__iter__"):
319 geometry_types = [geometry_types]
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)
325 geom_model = pin.buildGeomFromMJCF(
326 model, filename, geometry_type, mesh_loader=meshLoader
328 lst.append(geom_model)