Functions | |
def | _buildModelsFromMJCF (filename, root_joint=None, root_joint_name=None, verbose=False, meshLoader=None, geometry_types=None, contacts=False) |
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) |
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) |
def | buildModelsFromMJCF (filename, *args, **kwargs) |
Tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] | buildModelsFromSdf (filename, *args, **kwargs) |
Tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] | buildModelsFromUrdf (filename, *args, **kwargs) |
def | createDatas (*models) |
Variables | |
nle = pin.nonLinearEffects | |
|
private |
Definition at line 271 of file shortcuts.py.
|
private |
Definition at line 173 of file shortcuts.py.
|
private |
Definition at line 58 of file shortcuts.py.
def pinocchio.shortcuts.buildModelsFromMJCF | ( | filename, | |
* | args, | ||
** | kwargs | ||
) |
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. Arguments: - filename - name of the urdf file to load - package_dirs - where the meshes of the urdf are located. (default - None) - root_joint - Joint at the base of the model (default - None) - root_joint_name - Name for the root_joint (default - "root_joint") - verbose - print information of parsing (default - False) - meshLoader - object used to load meshes (default - hpp::fcl::MeshLoader) - geometry_types - Which geometry model to load. Can be pin.GeometryType.COLLISION, pin.GeometryType.VISUAL or both. (default - [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]) - contacts - Boolean to know if contraint models are wanted (default - False) Return: 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. Example: model, collision_model, visual_model = buildModelsFromMJCF(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
Definition at line 232 of file shortcuts.py.
Tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] pinocchio.shortcuts.buildModelsFromSdf | ( | filename, | |
* | args, | ||
** | kwargs | ||
) |
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. Arguments: - filename - name of the urdf file to load - package_dirs - where the meshes of the urdf are located. (default - None) - root_joint - Joint at the base of the model (default - None) - root_link_name - Name of the body to use as root of the model (default - "") - root_joint_name - Name for the root_joint (default - "root_joint") - 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. - verbose - print information of parsing (default - False) - meshLoader - object used to load meshes (default - hpp::fcl::MeshLoader) - geometry_types - Which geometry model to load. Can be pin.GeometryType.COLLISION, pin.GeometryType.VISUAL, both or None. (default - None]) Return: Tuple of the models, in this order : model, collision model, and visual model. Example: model, collision_model, visual_model = buildModelsFromSdf(filename, root_joint, root_link_name, parent_guidance, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name")
Definition at line 120 of file shortcuts.py.
Tuple[pin.Model, pin.GeometryModel, pin.GeometryModel] pinocchio.shortcuts.buildModelsFromUrdf | ( | filename, | |
* | args, | ||
** | kwargs | ||
) |
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. Arguments: - filename - name of the urdf file to load - package_dirs - where the meshes of the urdf are located. (default - None) - root_joint - Joint at the base of the model (default - None) - root_joint_name - Name for the root_joint (default - "root_joint") - verbose - print information of parsing (default - False) - meshLoader - object used to load meshes (default - hpp::fcl::MeshLoader) - geometry_types - Which geometry model to load. Can be pin.GeometryType.COLLISION, pin.GeometryType.VISUAL or both. (default - [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]) Return: Tuple of the models, in this order : model, collision model, and visual model. Example: model, collision_model, visual_model = buildModelsFromUrdf(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name") 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.
Definition at line 16 of file shortcuts.py.
def pinocchio.shortcuts.createDatas | ( | * | models | ) |
Call createData() on each Model or GeometryModel in input and return the results in a tuple. If one of the models is None, the corresponding data object in the result is also None.
Definition at line 111 of file shortcuts.py.
pinocchio.shortcuts.nle = pin.nonLinearEffects |
Definition at line 13 of file shortcuts.py.