better_launch.gazebo module

Additional functions for working with Gazebo, taking inspiration from simple_launch.

class better_launch.gazebo.GazeboBridge(topic: str, ros2_type: str = None, direction: Literal['ros2gz', 'gz2ros', 'bidirectional', '[', ']', '@'] = 'bidirectional', gazebo_type: str = None, *, remaps: dict[str, str] = None)

Bases: object

classmethod clock_bridge() GazeboBridge

Creates a GazeboBridge instance for bridging the /clock topic from Gazebo to ROS.

Returns

GazeboBridge

An instance of the GazeboBridge for the clock topic.

classmethod from_string(bridge: str, remaps: dict[str, str] = None) GazeboBridge

Extract the topic, ROS2 message type, direction, and gazebo message type from a bridge definition string.

Parameters

bridgestr

A bridge definition following the pattern <topic>@<ros2_type><direction><gazebo_type>.

remapsstr, optional

Topic remaps the bridge should use once it is started.

Returns

GazeboBridge

An instance with the aforementionend parameters.

Raises

ValueError

If the bridge string doesn’t match the expected pattern.

gazebo_message_types = {'actuator_msgs/msg/Actuators': 'gz.msgs.Actuators', 'builtin_interfaces/msg/Time': 'gz.msgs.Time', 'geometry_msgs/msg/Point': 'gz.msgs.Vector3d', 'geometry_msgs/msg/Pose': 'gz.msgs.Pose', 'geometry_msgs/msg/PoseArray': 'gz.msgs.Pose_V', 'geometry_msgs/msg/PoseStamped': 'gz.msgs.Pose', 'geometry_msgs/msg/PoseWithCovariance': 'gz.msgs.PoseWithCovariance', 'geometry_msgs/msg/PoseWithCovarianceStamped': 'gz.msgs.PoseWithCovariance', 'geometry_msgs/msg/Quaternion': 'gz.msgs.Quaternion', 'geometry_msgs/msg/Transform': 'gz.msgs.Pose', 'geometry_msgs/msg/TransformStamped': 'gz.msgs.Pose', 'geometry_msgs/msg/Twist': 'gz.msgs.Twist', 'geometry_msgs/msg/TwistStamped': 'gz.msgs.Twist', 'geometry_msgs/msg/TwistWithCovariance': 'gz.msgs.TwistWithCovariance', 'geometry_msgs/msg/TwistWithCovarianceStamped': 'gz.msgs.TwistWithCovariance', 'geometry_msgs/msg/Vector3': 'gz.msgs.Vector3d', 'geometry_msgs/msg/Wrench': 'gz.msgs.Wrench', 'geometry_msgs/msg/WrenchStamped': 'gz.msgs.Wrench', 'gps_msgs/msg/GPSFix': 'gz.msgs.NavSat', 'nav_msgs/msg/Odometry': 'gz.msgs.OdometryWithCovariance', 'rcl_interfaces/msg/ParameterValue': 'gz.msgs.Any', 'ros_gz_interfaces/msg/Altimeter': 'gz.msgs.Altimeter', 'ros_gz_interfaces/msg/Contact': 'gz.msgs.Contact', 'ros_gz_interfaces/msg/Contacts': 'gz.msgs.Contacts', 'ros_gz_interfaces/msg/Dataframe': 'gz.msgs.Dataframe', 'ros_gz_interfaces/msg/Entity': 'gz.msgs.Entity', 'ros_gz_interfaces/msg/Float32Array': 'gz.msgs.Float_V', 'ros_gz_interfaces/msg/GuiCamera': 'gz.msgs.GUICamera', 'ros_gz_interfaces/msg/JointWrench': 'gz.msgs.JointWrench', 'ros_gz_interfaces/msg/Light': 'gz.msgs.Light', 'ros_gz_interfaces/msg/ParamVec': 'gz.msgs.Param', 'ros_gz_interfaces/msg/SensorNoise': 'gz.msgs.SensorNoise', 'ros_gz_interfaces/msg/StringVec': 'gz.msgs.StringMsg_V', 'ros_gz_interfaces/msg/TrackVisual': 'gz.msgs.TrackVisual', 'ros_gz_interfaces/msg/VideoRecord': 'gz.msgs.VideoRecord', 'rosgraph_msgs/msg/Clock': 'gz.msgs.Clock', 'sensor_msgs/msg/BatteryState': 'gz.msgs.BatteryState', 'sensor_msgs/msg/CameraInfo': 'gz.msgs.CameraInfo', 'sensor_msgs/msg/FluidPressure': 'gz.msgs.FluidPressure', 'sensor_msgs/msg/Image': 'gz.msgs.Image', 'sensor_msgs/msg/Imu': 'gz.msgs.IMU', 'sensor_msgs/msg/JointState': 'gz.msgs.Model', 'sensor_msgs/msg/Joy': 'gz.msgs.Joy', 'sensor_msgs/msg/LaserScan': 'gz.msgs.LaserScan', 'sensor_msgs/msg/MagneticField': 'gz.msgs.Magnetometer', 'sensor_msgs/msg/NavSatFix': 'gz.msgs.NavSat', 'sensor_msgs/msg/PointCloud2': 'gz.msgs.PointCloudPacked', 'std_msgs/msg/Bool': 'gz.msgs.Boolean', 'std_msgs/msg/ColorRGBA': 'gz.msgs.Color', 'std_msgs/msg/Empty': 'gz.msgs.Empty', 'std_msgs/msg/Float32': 'gz.msgs.Float', 'std_msgs/msg/Float64': 'gz.msgs.Double', 'std_msgs/msg/Header': 'gz.msgs.Header', 'std_msgs/msg/Int32': 'gz.msgs.Int32', 'std_msgs/msg/String': 'gz.msgs.StringMsg', 'std_msgs/msg/UInt32': 'gz.msgs.UInt32', 'tf2_msgs/msg/TFMessage': 'gz.msgs.Pose_V', 'trajectory_msgs/msg/JointTrajectory': 'gz.msgs.JointTrajectory', 'vision_msgs/msg/Detection2D': 'gz.msgs.AnnotatedAxisAligned2DBox', 'vision_msgs/msg/Detection2DArray': 'gz.msgs.AnnotatedAxisAligned2DBox_V'}

Map from ROS2 message types to Gazebo message types.

classmethod joint_state_bridge(model: str) GazeboBridge

Creates a GazeboBridge instance for the bridging the joint states of a given model to ROS.

Parameters

modelstr

The model name to associate with the joint state topic.

Returns

GazeboBridge

An instance of the GazeboBridge for the joint state topic.

better_launch.gazebo.gazebo_launch(package: str, world_file: str, gz_args: list[str] = None, world_save_file: str = None, save_after: float = 10.0) None

Starts a Gazebo simulation with the specified world. If world_save_file is specified, the world will be saved as an SDF to that file after save_after seconds, including base world and spawned entities.

Parameters

packagestr,

A package to locate the world_file in. May be None (see [BetterLaunch.find][]).

world_filestr

Path to the primary world file for the simulation.

gz_args_type_, optional

Optional arguments to pass to the Gazebo simulator.

world_save_file_type_, optional

Path where the resulting SDF should be saved.

save_afterfloat, optional

Time in seconds after which the world SDF should be saved.

better_launch.gazebo.get_gazebo_axes_args(x: float = 0.0, y: float = 0.0, z: float = 0.0, yaw: float = 0.0, pitch: float = 0.0, roll: float = 0.0) dict[str, float]

Constructs a list of command-line arguments that can be used e.g. when spawning a new model.

Parameters

xfloat, optional

translation x component

yfloat, optional

translation y component

zfloat, optional

translation z component

yawfloat, optional

rotation yaw component

pitchfloat, optional

rotation pitch component

rollfloat, optional

rotation roll component

Returns

dict[str, float]

A dictionary containing the axes names and values. The axes names correspond to what Gazebo expects on the command line and so can be passed to e.g. [spawn_model][].

better_launch.gazebo.get_gazebo_version() str

For a short time, Gazebo rebranded to β€œIgnition” before returning to Gazebo again. This function returns the associated prefix.

Returns

str

The prefix indicating the type of Gazebo: β€œign” for Ignition Gazebo or β€œgz” for Gazebo Classic.

better_launch.gazebo.save_world(filepath: str, after: float = 5.0) None

Saves the current gazebo world to a file. Resolves any spawned URDF through their description parameter and converts to SDF.

Parameters

filepathstr

Path to the file to save the gazebo world to.

afterfloat, optional

How long to wait before saving.

better_launch.gazebo.spawn_image_bridge(*bridges: str | GazeboBridge, node_name: str = None, remaps: dict[str, str] = None, cmd_args: list[str] = None, qos: str = None, **kwargs) Node

Spawn a bridge to efficiently relay images from Gazebo to ROS2 (one direction only).

Parameters

bridgeslist[str | GazeboBridge]

The image topics to bridge. These can be specified as either Gazebo bridge definitions, [GazeboBridge][] instances. Also accepts regular topics, in which case the type is assumed to be sensor_msgs/Image.

node_namestr, optional

The name of the node running the bridge.

remapsdict[str, str], optional

How topics should be remapped in ROS2.

cmd_argslist[str], optional

Additional commandline arguments to the bridge executable.

qosstr, optional

The ROS2 quality of service definition to use. Note that this is not supported in all versions of ros-gz-image and may cause the bridge to terminate.

kwargsdict[str, Any]

Additional node arguments.

Returns

Node

The node running the bridge process.

Raises

ValueError

If a topic is passed which is not an image topic.

better_launch.gazebo.spawn_model(model_name: str, model: str, model_source: Literal['topic', 'file', 'string', 'param', 'auto'] = 'auto', spawn_args: dict[str, Any] = None) Node

Spawns a model into Gazebo under the given name from the specified topic or file.

The spawn_args dictionary can include additional options, such as the initial pose of the model.

Note that when spawning robot models this way, they typically also need a [convenience.joint_state_publisher][].

Parameters

model_namestr

The name of the model to spawn in the Gazebo environment.

modelstr

The model to spawn. The contents of this string depend on the model_source, but should ultimately lead to a full XML description.

model_sourcestr

Where to read the model from. Auto will try to guess the source based on the content of model: does it look like XML, is it a file, is it an existing topic? Otherwise assume it’s a ROS2 parameter.

spawn_argsdict[str, Any], optional

Additional arguments for spawning the model, such as pose and other options. See [get_gazebo_axes_args][] for defining the model’s orientation.

Returns

Node

The spawned node instance.

better_launch.gazebo.spawn_topic_bridge(*bridges: str | GazeboBridge, node_name: str = 'gz_bridge', remaps: dict[str, str] = None, cmd_args: list[str] = None, **kwargs) Node

Start a Gazebo topic bridge to relay messages between ROS2 and Gazebo.

Note that there is a separate function for bridging image topics more efficiently. See [spawn_image_bridge][].

Parameters

bridgeslist[str | GazeboBridge]

Definitions of topic bridges. This can be either a typical string (<topic>@<ros2_type><direction><gazebo_type>) or a [GazeboBridge][] instance. Note that in order to bridge services you will have to specify them as strings for now.

node_namestr, optional

The name of the bridge node.

remapsdict[str, str], optional

Any topic remaps you wish to apply to the bridge.

cmd_argslist[str], optional

Additional command line arguments to the gazebo bridge executable.

kwargsdict[str, Any]

Additional node arguments.

Returns

Node

The node running the bridge process.

better_launch.gazebo.spawn_world_transform(gazebo_world_frame: str = None) Node

Runs a static_transform_publisher to connect the ROS world frame and a Gazebo world frame, if the Gazebo world frame is specified and different from β€˜world’.

Parameters

gazebo_world_framestr, optional

The name of the Gazebo world frame. Uses [get_active_world_name][] if None.

Returns

Node

The spawned node instance.