yourdfpy package¶
Submodules¶
yourdfpy.urdf module¶
- class yourdfpy.urdf.Actuator(name: str, mechanical_reduction: Union[float, NoneType] = None, hardware_interfaces: List[str] = <factory>)[source]¶
Bases:
object
- class yourdfpy.urdf.Calibration(rising: float | NoneType = None, falling: float | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Collision(name: str, origin: numpy.ndarray | NoneType = None, geometry: yourdfpy.urdf.Geometry = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Dynamics(damping: float | NoneType = None, friction: float | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Geometry(box: yourdfpy.urdf.Box | NoneType = None, cylinder: yourdfpy.urdf.Cylinder | NoneType = None, sphere: yourdfpy.urdf.Sphere | NoneType = None, mesh: yourdfpy.urdf.Mesh | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Inertial(origin: numpy.ndarray | NoneType = None, mass: float | NoneType = None, inertia: numpy.ndarray | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Joint(name: str, type: str = None, parent: str = None, child: str = None, origin: numpy.ndarray = None, axis: numpy.ndarray = None, dynamics: yourdfpy.urdf.Dynamics | NoneType = None, limit: yourdfpy.urdf.Limit | NoneType = None, mimic: yourdfpy.urdf.Mimic | NoneType = None, calibration: yourdfpy.urdf.Calibration | NoneType = None, safety_controller: yourdfpy.urdf.SafetyController | NoneType = None)[source]¶
Bases:
object
- calibration: Calibration | None = None¶
- safety_controller: SafetyController | None = None¶
- class yourdfpy.urdf.Limit(effort: float | NoneType = None, velocity: float | NoneType = None, lower: float | NoneType = None, upper: float | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Link(name: str, inertial: Union[yourdfpy.urdf.Inertial, NoneType] = None, visuals: List[yourdfpy.urdf.Visual] = <factory>, collisions: List[yourdfpy.urdf.Collision] = <factory>)[source]¶
Bases:
object
- class yourdfpy.urdf.Material(name: str | NoneType = None, color: yourdfpy.urdf.Color | NoneType = None, texture: yourdfpy.urdf.Texture | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Mesh(filename: str, scale: float | numpy.ndarray | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Mimic(joint: str, multiplier: float | NoneType = None, offset: float | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Robot(name: str, links: List[yourdfpy.urdf.Link] = <factory>, joints: List[yourdfpy.urdf.Joint] = <factory>, materials: List[yourdfpy.urdf.Material] = <factory>, transmission: List[str] = <factory>, gazebo: List[str] = <factory>)[source]¶
Bases:
object
- class yourdfpy.urdf.SafetyController(soft_lower_limit: float | NoneType = None, soft_upper_limit: float | NoneType = None, k_position: float | NoneType = None, k_velocity: float | NoneType = None)[source]¶
Bases:
object
- class yourdfpy.urdf.Transmission(name: str, type: Union[str, NoneType] = None, joints: List[yourdfpy.urdf.TransmissionJoint] = <factory>, actuators: List[yourdfpy.urdf.Actuator] = <factory>)[source]¶
Bases:
object
- joints: List[TransmissionJoint]¶
- class yourdfpy.urdf.TransmissionJoint(name: str, hardware_interfaces: List[str] = <factory>)[source]¶
Bases:
object
- class yourdfpy.urdf.URDF(robot: Robot | None = None, build_scene_graph: bool = True, build_collision_scene_graph: bool = False, load_meshes: bool = True, load_collision_meshes: bool = False, filename_handler=None, mesh_dir: str = '', force_mesh: bool = False, force_collision_mesh: bool = True)[source]¶
Bases:
object
- property actuated_dof_indices¶
List of DOF indices per actuated joint. Can be used to reference configuration.
- property actuated_joint_indices¶
List of indices of all joints that are actuated, i.e., not of type mimic or fixed.
- property actuated_joint_names¶
List of names of actuated joints. This excludes mimic and fixed joints.
- property actuated_joints¶
List of actuated joints. This excludes mimic and fixed joints.
- property base_link¶
Name of URDF base/root link.
- Returns:
Name of base link of URDF model.
- Return type:
- property center_cfg¶
Return center configuration of URDF model by using the average of each joint’s limits if present, otherwise zero.
- Returns:
Default configuration of URDF model.
- Return type:
(n), float
- property cfg¶
Current configuration.
- Returns:
Current configuration of URDF model.
- Return type:
np.ndarray
- property collision_scene: Scene¶
A scene object representing the <collision> elements of the URDF model
- Returns:
A trimesh scene object.
- Return type:
trimesh.Scene
- contains(key, value, element=None) bool [source]¶
Checks recursively whether the URDF tree contains the provided key-value pair.
- property errors: list¶
A list with validation errors.
- Returns:
A list of validation errors.
- Return type:
- get_transform(frame_to, frame_from=None, collision_geometry=False)[source]¶
Get the transform from one frame to another.
- Parameters:
- Raises:
ValueError – Raised if scene graph wasn’t constructed during intialization.
- Returns:
Homogeneous transformation matrix
- Return type:
(4, 4) float
- property joint_map: dict¶
A dictionary mapping joint names to joint objects.
- Returns:
Mapping from joint name (str) to Joint.
- Return type:
- property joint_names¶
List of joint names.
- property link_map: dict¶
A dictionary mapping link names to link objects.
- Returns:
Mapping from link name (str) to Link.
- Return type:
- static load(fname_or_file, **kwargs)[source]¶
Load URDF file from filename or file object.
- Parameters:
fname_or_file (str or file object) – A filename or file object, file-like object, stream representing the URDF file.
**build_scene_graph (bool, optional) – Wheter to build a scene graph to enable transformation queries and forward kinematics. Defaults to True.
**build_collision_scene_graph (bool, optional) – Wheter to build a scene graph for <collision> elements. Defaults to False.
**load_meshes (bool, optional) – Whether to load the meshes referenced in the <mesh> elements. Defaults to True.
**load_collision_meshes (bool, optional) – Whether to load the collision meshes referenced in the <mesh> elements. Defaults to False.
**filename_handler ([type], optional) – Any function f(in: str) -> str, that maps filenames in the URDF to actual resources. Can be used to customize treatment of package:// directives or relative/absolute filenames. Defaults to None.
**mesh_dir (str, optional) – A root directory used for loading meshes. Defaults to “”.
**force_mesh (bool, optional) – Each loaded geometry will be concatenated into a single one (instead of being turned into a graph; in case the underlying file contains multiple geometries). This might loose texture information but the resulting scene graph will be smaller. Defaults to False.
**force_collision_mesh (bool, optional) – Same as force_mesh, but for collision scene. Defaults to True.
- Raises:
ValueError – If filename does not exist.
- Returns:
URDF model.
- Return type:
yourdfpy.URDF
- property num_actuated_joints¶
Number of actuated joints.
- Returns:
Number of actuated joints.
- Return type:
- property num_dofs¶
Number of degrees of freedom of actuated joints. Depending on the type of the joint, the number of DOFs might vary.
- Returns:
Degrees of freedom.
- Return type:
- property scene: Scene¶
A scene object representing the URDF model.
- Returns:
A trimesh scene object.
- Return type:
trimesh.Scene
- show(collision_geometry=False, callback=None)[source]¶
Open a simpler viewer displaying the URDF model.
- Parameters:
collision_geometry (bool, optional) – Whether to display the <collision> or <visual> elements. Defaults to False.
- split_along_joints(joint_type='floating', **kwargs)[source]¶
Split URDF model along a particular joint type. The result is a set of URDF models which together compose the original URDF.
- Parameters:
- Returns:
A list of tuples (np.ndarray, yourdfpy.URDF) whereas each homogeneous 4x4 matrix describes the root transformation of the respective URDF model w.r.t. the original URDF.
- Return type:
list[(np.ndarray, yourdfpy.URDF)]
- update_cfg(configuration)[source]¶
Update joint configuration of URDF; does forward kinematics.
- Parameters:
configuration (dict, list[float], tuple[float] or np.ndarray) – A mapping from joints or joint names to configuration values, or a list containing a value for each actuated joint.
- Raises:
ValueError – Raised if dimensionality of configuration does not match number of actuated joints of URDF model.
TypeError – Raised if configuration is neither a dict, list, tuple or np.ndarray.
- validate(validation_fn=None) bool [source]¶
Validate URDF model.
- Parameters:
validation_fn (function, optional) – A function f(list[yourdfpy.URDFError]) -> bool. None uses the strict handler (any error leads to False). Defaults to None.
- Returns:
Whether the model is valid.
- Return type:
- write_xml()[source]¶
Write URDF model to an XML element hierarchy.
- Returns:
XML data.
- Return type:
etree.ElementTree
- write_xml_file(fname)[source]¶
Write URDF model to an xml file.
- Parameters:
fname (str) – Filename of the file to be written. Usually ends in .urdf.
- write_xml_string(**kwargs)[source]¶
Write URDF model to a string.
- Returns:
String of the xml representation of the URDF model.
- Return type:
- property zero_cfg¶
Return the zero configuration.
- Returns:
The zero configuration.
- Return type:
np.ndarray
- exception yourdfpy.urdf.URDFAttributeValueError(msg)[source]¶
Bases:
URDFError
Raised when attribute value is not contained in the set of allowed values.
- exception yourdfpy.urdf.URDFBrokenRefError(msg)[source]¶
Bases:
URDFError
Raised when a referenced object is not found in the scope.
- exception yourdfpy.urdf.URDFIncompleteError(msg)[source]¶
Bases:
URDFError
Raised when needed data for an object isn’t there.
- exception yourdfpy.urdf.URDFMalformedError(msg)[source]¶
Bases:
URDFError
Raised when data is found to be corrupted in some way.
- exception yourdfpy.urdf.URDFSaveValidationError(msg)[source]¶
Bases:
URDFError
Raised when XML validation fails when saving.
- exception yourdfpy.urdf.URDFUnsupportedError(msg)[source]¶
Bases:
URDFError
Raised when some unexpectedly unsupported feature is found.
- class yourdfpy.urdf.Visual(name: str | NoneType = None, origin: numpy.ndarray | NoneType = None, geometry: yourdfpy.urdf.Geometry | NoneType = None, material: yourdfpy.urdf.Material | NoneType = None)[source]¶
Bases:
object
- yourdfpy.urdf.apply_visual_color(geom: Trimesh, visual: Visual, material_map: Dict[str, Material]) None [source]¶
Apply the color of the visual material to the mesh.
- Parameters:
geom – Trimesh to color.
visual – Visual description from XML.
material_map – Dictionary mapping material names to their definitions.
- yourdfpy.urdf.filename_handler_absolute2relative(fname, dir)[source]¶
A filename handler that turns an absolute file name into a relative one.
- yourdfpy.urdf.filename_handler_add_prefix(fname, prefix)[source]¶
A filename handler that adds a prefix.
- yourdfpy.urdf.filename_handler_ignore_directive(fname)[source]¶
A filename handler that removes anything before (and including) ‘://’.
- yourdfpy.urdf.filename_handler_ignore_directive_package(fname)[source]¶
A filename handler that removes the ‘package://’ directive and the package it refers to. It subsequently calls filename_handler_ignore_directive, i.e., it removes any other directive.
- yourdfpy.urdf.filename_handler_meta(fname, filename_handlers)[source]¶
A filename handler that calls other filename handlers until the resulting file name points to an existing file.
- yourdfpy.urdf.filename_handler_null(fname)[source]¶
A lazy filename handler that simply returns its input.
yourdfpy.viz module¶
Script for visualizing a robot from a URDF.
- yourdfpy.viz.generate_joint_limit_trajectory(urdf_model, loop_time)[source]¶
Generate a trajectory for all actuated joints that interpolates between joint limits. For continuous joint interpolate between [0, 2 * pi].
- yourdfpy.viz.main(args)[source]¶
Wrapper allowing string arguments in a CLI fashion.
- Parameters:
args (List[str]) – command line parameters as list of strings (for example
["--verbose", "42"]
).
- yourdfpy.viz.parse_args(args)[source]¶
Parse command line parameters
- Parameters:
args (List[str]) – command line parameters as list of strings (for example
["--help"]
).- Returns:
command line parameters namespace
- Return type:
- yourdfpy.viz.run()[source]¶
Calls
main()
passing the CLI arguments extracted fromsys.argv
.This function can be used as entry point to create console scripts with setuptools.