drake_ready_urdf_converter

Submodules

Classes

class brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.config.DrakeReadyURDFConverterConfig(output_urdf_file_path: str = None, overwrite_old_logs: bool = False, overwrite_old_models: bool = False, log_file_name: str = 'conversion.log', mesh_replacement_strategies: MeshReplacementStrategies = MeshReplacementStrategies(collision_meshes=<MeshReplacementStrategy.kWithObj: 1>, visual_meshes=<MeshReplacementStrategy.kWithObj: 1>), add_missing_actuators: bool = True, replace_colors_with: List[float] = None, coacd_log_level: str = 'info')[source]

Description

A dataclass that specifies how the DrakeReadyURDFConverter should convert the URDF file.

Attributes

output_urdf_file_path: str

The path where the converted URDF file will be saved. If None, it defaults to the models directory.

coacd_log_level: str

The log level for the coacd tool. Options are “off”, “info”, “error”.

class brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.config.MeshReplacementStrategies(collision_meshes: MeshReplacementStrategy = MeshReplacementStrategy.kWithObj, visual_meshes: MeshReplacementStrategy = MeshReplacementStrategy.kWithObj)[source]

Description

A dataclass that specifies the different strategies for replacing mesh files in: - the <collision> section of the URDF - the <visual> section of the URDF

class brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.config.MeshReplacementStrategy(*values)[source]

Description

The different strategies for replacing mesh files.

Options are:

kDoNotReplace kWithObj kWithMinimalEnclosingCylinder kWithConvexDecomposition

Usage

from brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.config import MeshReplacementStrategy
# or
# from brom_drake.all import MeshReplacementStrategy

# Selecting the strategy to replace meshes with OBJ files
strategy = MeshReplacementStrategy.kWithObj
class brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.converter.DrakeReadyURDFConverter(original_urdf_filename: str, config: DrakeReadyURDFConverterConfig = DrakeReadyURDFConverterConfig(output_urdf_file_path=None, overwrite_old_logs=False, overwrite_old_models=False, log_file_name='conversion.log', mesh_replacement_strategies=MeshReplacementStrategies(collision_meshes=<MeshReplacementStrategy.kWithObj: 1>, visual_meshes=<MeshReplacementStrategy.kWithObj: 1>), add_missing_actuators=True, replace_colors_with=None, coacd_log_level='info'))[source]

Description

This class is used to convert a URDF file into a Drake-compatible URDF file. It makes the following considerations when parsing a URDF file:

  • If a mesh file is not supported by the Drake parser, then it will convert it into a .obj file (which is supported).

  • If a joint in the URDF file is not “fixed” (i.e., it is actuated) and the parser finds no transmission element for it, then it will add a transmission element to the URDF file.

Parameters

original_urdf_filename: str

The path to the original URDF file.

config: DrakeReadyURDFConverterConfig (optional)

The configuration for the URDF converter. This controls:

  • whether or not to convert unsupported mesh files

  • whether or not to add missing transmissions

  • etc.

convert_collision_element(collision_elt: Element) List[Element][source]

Description

This method will convert the collision element in the URDF file.

Parameters

collision_elt: xml.etree.ElementTree.Element

The collision element that we want to convert.

Returns

List[xml.etree.ElementTree.Element]

The collision elements that will replace the original collision element. Usually, this is a list of length 1, but in some cases (e.g., convex decomposition) it may be longer.

convert_geometry_element(geometry_elt: Element, replacement_strategy: MeshReplacementStrategy) Element[source]

Description

This method will convert the geometry element in the URDF (i.e., an XML) file according to the conversion strategy provided as input.

Parameters

geometry_elt: xml.etree.ElementTree.Element

The geometry element that we want to convert.

replacement_strategy: MeshReplacementStrategy

The strategy to use for replacing mesh files.

Returns

xml.etree.ElementTree.Element

The new geometry element.

convert_mesh_element(mesh_elt_in: Element) Element[source]

Description

This method will convert the mesh element in the URDF file into a Drake-compatible mesh element.

Parameters

mesh_elt_in: xml.etree.ElementTree.Element

The mesh element that we want to convert.

Returns

xml.etree.ElementTree.Element

The new mesh element.

convert_tree(current_tree: ElementTree) List[ElementTree][source]

Description

This recursive method is used to parse each element of the xml element tree and replace the components that are not supported by the Drake URDF parser.

Parameters

current_tree: xml.etree.ElementTree.ElementTree

The current tree that we are parsing.

Returns

List[xml.etree.ElementTree.ElementTree]

The new trees that has been converted.

convert_tree_element(elt: Element) List[Element][source]

Description

This method is used to transform one element in the XML tree into an eleemnt that that Drake URDF parser can handle. If necessary, it will create a new 3d model file and place it into the right directory.

Parameters

elt: xml.etree.ElementTree.Element

An element in the ElementTree that we would like to convert into a Drake-ready element.

Returns

List[xml.etree.ElementTree.Element]

The new elements that has been converted.

convert_urdf() Path[source]

Description

Converts the original URDF file into a Drake-compatible URDF file.

Returns

Path

The path to the new URDF file.

convert_visual_element(visual_elt: Element) Element[source]

Description

This method will convert the collision element in the URDF file.

For now, this is very similar to the collision element handling, but it may change in the future.

Parameters

visual_elt: xml.etree.ElementTree.Element

The visual element that we want to convert.

Returns

xml.etree.ElementTree.Element

The new visual element.

create_logger() Logger[source]

Description

This method configures the logging logger for the URDF conversion.

Returns

logging.Logger

The configured logger.

create_new_material_element(material_elt: Element)[source]

Description

This method will handle the material element in the URDF file. Specifically, it will check to see if the user wants us to assign a color to the material element. If so, then we will assign the color to the material element.

This is useful when attempting to add transmissions to the URDF file later on.

Parameters

material_elt: xml.etree.ElementTree.Element

The material element that we want to handle.

Returns

None, but modifies the material element.

create_obj_to_replace_mesh_file(mesh_file_name: str) str[source]

Description

This function will create an .obj file to replace the .stl or .dae file that is given in mesh file “mesh_file_name”.

Parameters

mesh_file_name: str

The name of the mesh file that we want to convert.

Returns

str

The name of the new .obj file that has been created.

handle_joint_element(joint_elt: Element)[source]

Description

This method will handle the joint element in the URDF file. Specifically, it will check to see if the joint is actuated and (if it is) add it to the list of actuated joints.

This is useful when attempting to add transmissions to the URDF file later on.

Parameters

joint_elt: xml.etree.ElementTree.Element

The joint element that we want to handle.

Returns

None

log(message: str)[source]

Description

Logs a message to the logging.logger.

Parameters

message: str

The message that we want to log.

Returns

None

replace_element_with_enclosing_cylinder(collision_elt: Element) Element[source]

Description

This method will replace the geometry element with an enclosing cylinder.

Parameters

collision_elt: xml.etree.ElementTree.Element

The collision element that we want to replace.

Returns

xml.etree.ElementTree.Element

The new collision element with the enclosing cylinder.

class brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.file_manager.DrakeReadyURDFConverterFileManager(original_urdf_path: Path, models_directory: Path = PosixPath('brom/models'), log_file_name: str = None, _output_urdf_path: str | Path = None)[source]

Description

A dataclass that specifies how the DrakeReadyURDFConverter should manage files.

clean_up_models_dir()[source]

Description

This method will clean up the models directory.

file_path_in_context_of_urdf_dir(file_path: str | Path) Path[source]

Description

This method returns the given file_path’s Path when taken into context of where the urdf lies.

Parameters

file_path: str or Path

The file path to convert

Returns

Path

The file path with added context of the INPUT URDF file.

output_file_directory() Path[source]

Description

Returns the directory where the output URDF file will be saved. If the output_urdf_file_path is not specified, it defaults to the models_directory.

Returns

Path

The directory where the output URDF file will be saved.

output_urdf_file_name() str[source]

Description

Creates the output filename based on the original filename.

Returns

str

The name of the output URDF file

property output_urdf_path: Path

Description

Returns the path where the output URDF file will be saved. If the output_urdf_file_path is not specified, it defaults to the models_directory with the same name as the original URDF file.

Returns

Path

The path where the output URDF file will be saved.

class brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.mesh_file_converter.MeshFileConverter(mesh_file_path: str, urdf_dir: Path, new_urdf_dir: Path, logger: Logger)[source]

Description

This class will convert a mesh file to a different format using the trimesh library.

Parameters

mesh_file_path: str

The path to the mesh file that we want to convert. This path should be given RELATIVE to the URDF that we are converting.

urdf_dir: Path

The directory where the URDF file is located.

new_urdf_dir: Path

The directory where the new URDF file will be saved.

logger: logging.Logger

The logger to use for logging messages.

define_output_path(output_mesh_file: Path = None) Path[source]

Description

This function will define the output path for the CONVERTED mesh file.

Parameters

output_mesh_file: Path

The output path for the mesh file.

Returns

converted_mesh_file_path: Path

The output path for the converted mesh file. This should be the same as the input mesh file, if given.

find_file_path_in_package(max_depth: int = 10) Path[source]

Description

This method will find the file path in the package.

param max_depth:

The maximum depth to search for the package directory.

return:

mesh_file_path_is_relative()[source]
Description:

This function will check if the mesh file path is relative.

true_mesh_file_path(max_depth: int = 10) Path[source]

Description

This function will return the true mesh file path.

Functions

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.util.create_transmission_element_for_joint(actuated_joint_name: str) Element[source]

Description

This function creates a transmission element for the given joint.

Parameters

actuated_joint_name: str

The name of the joint that will be actuated

Returns

transmission_element: xml.etree.ElementTree.Element

The transmission element for the given joint.

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.util.does_drake_parser_support(filename: str) bool[source]

Description

This function cleanly answers whether the given 3d object file is supported by Drake.

Parameters

filename: str

The name of the file to check.

Returns

does_support: bool

True if the file is supported by Drake, False otherwise.

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.util.find_mesh_file_path_in(collision_element: Element) Path | None[source]

Description

This function finds the mesh filename in the given collision element.

Parameters

collision_element: ET.Element

The collision element to search for a mesh filename

Returns

mesh_file_path: Path|None

The mesh filename if found, otherwise None

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.util.get_mesh_element_in(collision_element: Element) Element | None[source]

Description

This function finds the mesh element in the given collision element.

Parameters

collision_element: ET.Element

The collision element to search for a mesh element

Returns

new_element: ET.Element or None

The mesh element if found, otherwise None

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.util.tree_contains_transmission_for_joint(tree: ElementTree, actuated_joint_name: str) bool[source]

Description

This function determines if the given tree contains a transmission element for the given actuated joint.

Parameters

tree: xml.etree.ElementTree.ElementTree

The tree to search for the transmission element.

actuated_joint_name: str

The name of the joint that will be actuated.

Returns

transmission_exists: bool

True if the tree contains a transmission element for the given joint,

Variables

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.converter.DEFAULT_BROM_MODELS_DIR = './brom/models'

str(object=’’) -> str str(bytes_or_buffer[, encoding[, errors]]) -> str

Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.__str__() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to ‘strict’.

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.converter.URDF_CONVERSION_LEVEL = 21

int([x]) -> integer int(x, base=10) -> integer

Convert a number or string to an integer, or return 0 if no arguments are given. If x is a number, return x.__int__(). For floating point numbers, this truncates towards zero.

If x is not a number or if base is given, then x must be a string, bytes, or bytearray instance representing an integer literal in the given base. The literal can be preceded by ‘+’ or ‘-’ and be surrounded by whitespace. The base defaults to 10. Valid bases are 0 and 2-36. Base 0 means to interpret the base from the string as an integer literal. >>> int(‘0b100’, base=0) 4

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.converter.URDF_CONVERSION_LOG_LEVEL_NAME = 'BROM_URDF_CONVERSION'

str(object=’’) -> str str(bytes_or_buffer[, encoding[, errors]]) -> str

Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.__str__() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to ‘strict’.

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.file_manager.DEFAULT_BROM_MODELS_DIR = './brom/models'

str(object=’’) -> str str(bytes_or_buffer[, encoding[, errors]]) -> str

Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.__str__() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to ‘strict’.

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.mesh_file_converter.URDF_CONVERSION_LOG_LEVEL_NAME = 'BROM_URDF_CONVERSION'

str(object=’’) -> str str(bytes_or_buffer[, encoding[, errors]]) -> str

Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.__str__() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to ‘strict’.

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.util.URDF_CONVERSION_LEVEL = 21

int([x]) -> integer int(x, base=10) -> integer

Convert a number or string to an integer, or return 0 if no arguments are given. If x is a number, return x.__int__(). For floating point numbers, this truncates towards zero.

If x is not a number or if base is given, then x must be a string, bytes, or bytearray instance representing an integer literal in the given base. The literal can be preceded by ‘+’ or ‘-’ and be surrounded by whitespace. The base defaults to 10. Valid bases are 0 and 2-36. Base 0 means to interpret the base from the string as an integer literal. >>> int(‘0b100’, base=0) 4

brom_drake.file_manipulation.urdf.drake_ready_urdf_converter.util.URDF_CONVERSION_LOG_LEVEL_NAME = 'BROM_URDF_CONVERSION'

str(object=’’) -> str str(bytes_or_buffer[, encoding[, errors]]) -> str

Create a new string object from the given object. If encoding or errors is specified, then the object must expose a data buffer that will be decoded using the given encoding and error handler. Otherwise, returns the result of object.__str__() (if defined) or repr(object). encoding defaults to sys.getdefaultencoding(). errors defaults to ‘strict’.