better_launch.convenience module

Additional convenience methods that aren’t general enough to be added to the main namespace.

better_launch.convenience.joint_state_publisher(use_gui: bool = False, node_name: str = None, **kwargs) Node

Starts a joint_state_publisher or joint_state_publisher_gui node.

Parameters

use_guibool, optional

Whether to use the GUI version of the joint_state_publisher.

node_namestr, optional

The name of the node. If not provided the name of the executable will be used. Will be anonymized unless anonymous=False is passed.

**kwargsdict, optional

Additional arguments to pass to the node (e.g. name, remaps, params, etc.). See [BetterLaunch.node][].

Returns

Node

The spawned node instance.

better_launch.convenience.read_robot_description(package: str, description_file: str, subdir: str = None, *, xacro_args: list[str] = None) str | None

Returns the contents of a robot description after a potential xacro parse.

The file is resolved using [BetterLaunch.find][]. If the description file ends with .urdf and xacro_args is not provided, it reads the URDF file directly. Otherwise it runs xacro to generate the URDF from a .xacro file.

Parameters

packagestr

The package where the robot description file is located. May be None to use this launch file’s package (see [BetterLaunch.find][]).

description_filestr

The name of the robot description file (URDF or XACRO).

subdirstr, optional

A path fragment the description file must be located in.

xacro_argslist of str, optional

Additional arguments to pass to xacro when processing .xacro files.

Returns

str | None

The parsed URDF XML as a string if successful, None otherwise.

Raises

ValueError

If the xacro command encountered an error while processing the file.

better_launch.convenience.robot_state_publisher(package: str, description_file: str, subdir: str = None, *, xacro_args: list[str] = None, node_name: str = None, **kwargs) Node

Start a Robot State Publisher node using the given URDF/Xacro file. The file is resolved using [BetterLaunch.find][].

Parameters

packagestr

The name of the package containing the robot description file. May be None to use this launch file’s package (see [BetterLaunch.find][]).

description_filestr

The name of the robot description for the robot. Typically a .sdf, .urdf or .xacro file.

subdirstr, optional

A path fragment the description file must be located in.

xacro_argslist of str, optional

Additional arguments to pass to the Xacro processor when processing .xacro files.

node_namestr, optional

The name of the node. If not provided the name of the executable will be used. Will be anonymized unless anonymous=False is passed.

**kwargsdict, optional

Additional arguments for the node, such as remappings or parameters.

Returns

Node

The spawned node instance.

better_launch.convenience.rviz(package: str = None, configfile: str = None, subdir: str = None, *, extra_args: list[str] = None) Node

Runs RViz2 with the given config file and optional warning level suppression.

Parameters

packagestr, optional

Path to locate the config file in (if one is specified).

configfilestr, optional

Path to the RViz2 configuration file which will be resolved by [BetterLaunch.find][]. Otherwise RViz2 will run with the default config.

subdirstr, optional

A path fragment the config file must be located in.

extra_argslist[str], optional

Additional args to pass to the RViz2 executable.

Returns

Node

The spawned node instance.

better_launch.convenience.static_transform_publisher(parent_frame: str, child_frame: str, pos: Sequence[float] = None, rot: Sequence[float] = None) Node

Publish a static transform between two frames.

Parameters

parent_framestr

The parent or source frame.

child_framestr

The child or target frame.

posSequence[float], optional

The xyz-translation from parent to child frame. You may also pass a sequence of 6 or 7 floats in order to specify a full pose. In this case, rot will be ignored.

rotSequence[float], optional

The rotation between the parent and child frame. If length is 3, the values are interpreted as roll-pitch-yaw euler angles. If length is 4, an xyzw-quaternion is assumed.

Returns

Node

The node running the publisher process.

Raises

ValueError

If pos or rot have the wrong length.