Main Content

Emergency Braking of Ego Vehicle in CARLA Simulator Using Simulink and CARLA ROS Bridge

This example shows how to set up, connect to, and control an ego vehicle in the CARLA simulator using ROS Toolbox™.

Overview

You control the CARLA ego vehicle by sending steering, braking, and throttle control signals to a vehicle controls publisher using Simulink® software. The model reads point cloud data from the front camera, odometer, and lidar sensors of the ego vehicle. The point cloud processor removes ground reflection and calculates the average distance of the objects in front of the ego vehicle. The model sends the calculated distance to the emergency braking unit which issues a braking command if the distance drops below 10 meters.

Setup

Install the latest CARLA simulator on your host machine. This example uses the binary installation of version 0.9.13 of the CARLA Simulator.

Download and install the ROS Virtual Machine. This virtual machine is based on the Ubuntu® Linux® operating system and is pre-configured to support the examples in ROS Toolbox™.

Here is the diagram depicts the setup of this example.

Step 1: Start the CARLA Server

  • On your windows host machine, navigate to the installed location of CARLA. Click on the CarlaUE4.exe to start the CARLA server.

Step 2: Setup the CARLA ROS bridge

  • Launch the virtual machine.

  • On the Ubuntu desktop, click the ROS Noetic Core Terminal shortcut to start the ROS master. Once the master is launched, please note down the ROS_MASTER_URI.

  • On the Ubuntu desktop, click the ROS Noetic Terminal shortcut to start the ROS terminal. Run this command to setup the CARLA ROS bridge environment:

. ~/carla-ros-bridge/catkin_ws/devel/setup.bash

Step 3: Launch Ego Vehicle in Town03 using CARLA client

  • In the same terminal, run the follow command to launch the ego vehicle in the Town03 environment of CARLA simulator. The follow command launches the ego vehicle near to the gas station.

  • Run this command to change the host address to the host address of your machine:

roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch host:=172.18.226.60 timeout:=60000 town:='Town03' spawn_point:=-25,-134,0.5,0,0,-90

Control Ego Vehicle in CARLA Using Simulink

Connect Simulink to the ROS master running in the VM Ware.

rosinit('http://172.18.226.233:11311')
Initializing global node /matlab_global_node_37271 with NodeURI http://172.18.226.60:60619/ and MasterURI http://172.18.226.233:11311.

Ensure that you can access ROS topics related to the CARLA simulator by running the following introspection command.

rostopic list
/carla/ego_vehicle/collision                      
/carla/ego_vehicle/control/set_transform          
/carla/ego_vehicle/enable_autopilot               
/carla/ego_vehicle/gnss                           
/carla/ego_vehicle/lane_invasion                  
/carla/ego_vehicle/odometry                       
/carla/ego_vehicle/rgb_view/image                 
/carla/ego_vehicle/vehicle_control_cmd_manual     
/carla/ego_vehicle/vehicle_control_manual_override
/carla/ego_vehicle/vehicle_info                   
/carla/ego_vehicle/vehicle_status                 
/carla/status                                     
/clock                                            
/initialpose                                      
/rosout                                           
/rosout_agg                                       
/tf                                               

Open the Simulink model.

open_system('EmergencybrakingofCarlaEgoVehicle');

The model shows the point cloud data from the lidar sensor that the vehicle uses to measure the distance to the obstacle. When the distance is below 10 meters, the emergency braking system sends a braking command to the vehicle.

Run the Simulink model. The ego vehicle automatically stops 10 meters ahead of the vehicle in front of it at the gas station. The CARLA ROS manual control terminal shows the stationary vehicle with the brake applied.

Shut down the ROS network.

rosshutdown
Shutting down global node /matlab_global_node_37271 with NodeURI http://172.18.226.60:60619/ and MasterURI http://172.18.226.233:11311.