The carla_ros_bridge
package is the main package needed to run the basic ROS bridge functionality. In this section you will learn how to prepare the ROS environment, run the ROS bridge, how to configure the settings, usage of synchronous mode, controlling the ego vehicle and a summary of the subscriptions, publications and services available.
- Setting the ROS environment
- Running the ROS bridge
- Configuring CARLA settings
- Using the ROS bridge in synchronous mode
- Ego vehicle control
- ROS API
The ROS bridge supports both ROS 1 and ROS 2 using separate implementations with a common interface. When you want to run the ROS bridge you will have to set your ROS environment according to your ROS version in every terminal that you use:
The command to run depends on whether you installed the ROS bridge via the Debian package or via the source build. You will also need to change the ROS version in the path for the Debian option:
# For debian installation of ROS bridge. Change the command according to your installed version of ROS.
source /opt/carla-ros-bridge/<melodic/noetic>/setup.bash
# For GitHub repository installation of ROS bridge
source ~/carla-ros-bridge/catkin_ws/devel/setup.bash
source ./install/setup.bash
Once you have set your ROS environment and have a CARLA server running, you will need to start the carla_ros_bridge
package before being able to use any of the other packages. To do that, run the following command:
# ROS 1
roslaunch carla_ros_bridge carla_ros_bridge.launch
# ROS 2
ros2 launch carla_ros_bridge carla_ros_bridge.launch.py
There are other launchfiles that combine the above functionality of starting the ROS bridge at the same time as starting other packges or plugins:
carla_ros_bridge_with_example_ego_vehicle.launch
(ROS 1) andcarla_ros_bridge_with_example_ego_vehicle.launch.py
(ROS 2) start the ROS bridge along with thecarla_spawn_objects
andcarla_manual_control
packages.
Configurations should be set either within the launchfile or passed as an argument when running the file from the command line, for example:
roslaunch carla_ros_bridge carla_ros_bridge.launch passive:=True
The following settings are available:
- use_sim_time: This should be set to True to ensure that ROS is using simulation time rather than system time. This parameter will synchronize the ROS
/clock
topic with CARLA simulation time. - host and port: Network settings to connect to CARLA using a Python client.
- timeout: Time to wait for a successful connection to the server.
- passive: Passive mode is for use in scynchronous mode. When enabled, the ROS bridge will take a backseat and another client must tick the world. ROS bridge will wait for all expected data from all sensors to be received.
- synchronous_mode:
- If false: Data is published on every
world.on_tick()
and everysensor.listen()
callback. - If true (default): ROS bridge waits for all the sensor messages expected before the next tick. This might slow down the overall simulation but ensures reproducible results.
- If false: Data is published on every
- synchronous_mode_wait_for_vehicle_control_command: In synchronous mode, pauses the tick until a vehicle control is completed.
- fixed_delta_seconds: Simulation time (delta seconds) between simulation steps. It must be lower than 0.1. Take a look at the documentation to learn more about this.
- ego_vehicle: Role names to identify ego vehicles. Relevant topics will be created so these vehicles will be able to be controlled from ROS.
- town: Either use an available CARLA town (eg. 'town01') or an OpenDRIVE file (ending in
.xodr
). - register_all_sensors:
- If false: Only sensors spawned by the bridge are registered.
- If true (default): All the sensors present in the simulation are registered.
The ROS bridge operates in synchronous mode by default. It will wait for all sensor data that is expected within the current frame to ensure reproducible results.
When running multiple clients in synchronous mode, only one client is allowed to tick the world. The ROS bridge will by default be the only client allowed to tick the world unless passive mode is enabled. Enabling passive mode in ros-bridge/carla_ros_bridge/config/settings.yaml
will make the ROS bridge step back and allow another client to tick the world. Another client must tick the world, otherwise CARLA will freeze.
If the ROS bridge is not in passive mode (ROS bridge is the one ticking the world), then there are two ways to send step controls to the server:
- Send a message to the topic
/carla/control
with acarla_msgs.CarlaControl
message. - Use the Control rqt plugin. This plugin launches a new window with a simple interface. It is then used to manage the steps and publish in the
/carla/control
topic. To use it, run the following command with CARLA in synchronous mode:
rqt --standalone rqt_carla_control
There are two modes to control the ego vehicle:
- Normal mode - reading commands from
/carla/<ROLE NAME>/vehicle_control_cmd
- Manual mode - reading commands from
/carla/<ROLE NAME>/vehicle_control_cmd_manual
. This allows to manually override Vehicle Control Commands published by a software stack.
You can toggle between the two modes by publishing to /carla/<ROLE NAME>/vehicle_control_manual_override
. For an example of this being used see Carla Manual Control.
To test steering from the command line:
1. Launch the ROS Bridge with an ego vehicle:
# ROS 1
roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch
# ROS 2
ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py
2. In another terminal, publish to the topic /carla/<ROLE NAME>/vehicle_control_cmd
# Max forward throttle with max steering to the right
# for ros1
rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10
# for ros2
ros2 topic pub /carla/ego_vehicle/vehicle_control_cmd carla_msgs/CarlaEgoVehicleControl "{throttle: 1.0, steer: 1.0}" -r 10
The current status of the vehicle can be received via topic /carla/<ROLE NAME>/vehicle_status
. Static information about the vehicle can be received via /carla/<ROLE NAME>/vehicle_info
.
It is possible to use AckermannDrive messages to control the ego vehicles. This can be achieved through the use of the CARLA Ackermann Control package.
Topic | Type | Description |
---|---|---|
/carla/debug_marker |
visualization_msgs/MarkerArray | Draws markers in the CARLA world. |
/carla/weather_control |
carla_msgs/CarlaWeatherParameters | Set the CARLA weather parameters |
/clock |
rosgraph_msgs/Clock | Publishes simulated time in ROS. |
!!! Note
When using debug_marker
, be aware that markers may affect the data published by sensors. Supported markers include: arrow (specified by two points), points, cube and line strip.
Topic | Type | Description |
---|---|---|
/carla/status |
carla_msgs/CarlaStatus | Read the current status of CARLA |
/carla/world_info |
carla_msgs/CarlaWorldInfo | Information about the current CARLA map. |
/clock |
rosgraph_msgs/Clock | Publishes simulated time in ROS. |
/rosout |
rosgraph_msgs/Log | ROS logging. |
Topic | Type | Description |
---|---|---|
/carla/destroy_object |
carla_msgs/DestroyObject.srv | Destroys an object |
/carla/get_blueprints |
carla_msgs/GetBlueprints.srv | Gets blueprints |
/carla/spawn_object |
carla_msgs/SpawnObject.srv | Spawn an object |