Coder Social home page Coder Social logo

ros-bridge's Introduction

ROS bridge for CARLA simulator

This ROS package aims at providing a simple ROS bridge for CARLA simulator.

Important Note: This documentation is for CARLA versions newer than 0.9.4.

rviz setup depthcloud

short video

Features

  • Cameras (depth, segmentation, rgb) support
  • Transform publications
  • Manual control using ackermann msg
  • Handle ROS dependencies
  • Marker/bounding box messages for cars/pedestrian
  • Lidar sensor support
  • Rosbag in the bridge (in order to avoid rosbag record -a small time errors)
  • Add traffic light support

Setup

Create a catkin workspace and install carla_ros_bridge package

#setup folder structure
mkdir -p ~/carla-ros-bridge/catkin_ws/src
cd ~/carla-ros-bridge
git clone https://github.com/carla-simulator/ros-bridge.git
cd catkin_ws/src
ln -s ../../ros-bridge
source /opt/ros/kinetic/setup.bash
cd ..

#install required ros-dependencies
rosdep update
rosdep install --from-paths src --ignore-src -r

#build
catkin_make

For more information about configuring a ROS environment see http://wiki.ros.org/ROS/Tutorials/InstallingandConfiguringROSEnvironment

Start the ROS bridge

First run the simulator (see carla documentation: http://carla.readthedocs.io/en/latest/)

./CarlaUE4.sh -windowed -ResX=320 -ResY=240 -benchmark -fps=10

Wait for the message:

Waiting for the client to connect...

Then start the ros bridge (choose one option):

export PYTHONPATH=$PYTHONPATH:<path/to/carla/>/PythonAPI/<your_egg_file>
source ~/carla-ros-bridge/catkin_ws/devel/setup.bash

# Option 1: start the ros bridge
roslaunch carla_ros_bridge carla_ros_bridge.launch

# Option 2: start the ros bridge together with RVIZ
roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch

# Option 3: start the ros bridge together with an example ego vehicle
roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch

You can setup the ros bridge configuration carla_ros_bridge/config/settings.yaml.

As we have not spawned any vehicle and have not added any sensors in our carla world there would not be any stream of data yet.

You can make use of the CARLA Python API script manual_control.py.

cd <path/to/carla/>
python manual_control.py --rolename=ego_vehicle

This spawns a carla client with role_name='ego_vehicle'. If the rolename is within the list specified by ROS parameter /carla/ego_vehicle/rolename, the client is interpreted as an controllable ego vehicle and all relevant ROS topics are created.

To simulate traffic, you can spawn automatically moving vehicles by using spawn_npc.py from CARLA Python API.

Available ROS Topics

Ego Vehicle

Odometry

Topic Type
/carla/<ROLE NAME>/odometry nav_msgs.Odometry

Sensors

The ego vehicle sensors are provided via topics with prefix /carla/ego_vehicle/<sensor_topic>

Currently the following sensors are supported:

Camera

Topic Type
/carla/<ROLE NAME>/camera/rgb/<SENSOR ROLE NAME>/image_color sensor_msgs.Image
/carla/<ROLE NAME>/camera/rgb/<SENSOR ROLE NAME>/camera_info sensor_msgs.CameraInfo

Lidar

Topic Type
/carla/<ROLE NAME>/lidar/<SENSOR ROLE NAME>/point_cloud sensor_msgs.PointCloud2

GNSS

Topic Type
/carla/<ROLE NAME>/gnss/front/gnss sensor_msgs.NavSatFix

Collision Sensor

Topic Type
/carla/<ROLE NAME>/collision carla_msgs.CarlaCollisionEvent

Lane Invasion Sensor

Topic Type
/carla/<ROLE NAME>/lane_invasion carla_msgs.CarlaLaneInvasionEvent

Control

Topic Type
/carla/<ROLE NAME>/vehicle_control_cmd (subscriber) carla_msgs.CarlaEgoVehicleControl
/carla/<ROLE NAME>/vehicle_status carla_msgs.CarlaEgoVehicleStatus
/carla/<ROLE NAME>/vehicle_info carla_msgs.CarlaEgoVehicleInfo

You can stear the ego vehicle from the commandline by publishing to the topic /carla/<ROLE NAME>/vehicle_control_cmd.

Examples for a ego vehicle with role_name 'ego_vehicle':

Max forward throttle:

 rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_ros_bridge/CarlaEgoVehicleControl "{throttle: 1.0, steer: 0.0}" -r 10

Max forward throttle with max steering to the right:

 rostopic pub /carla/ego_vehicle/vehicle_control_cmd carla_ros_bridge/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

Carla Ackermann Control

In certain cases, the Carla Control Command is not ideal to connect to an AD stack. Therefore a ROS-based node carla_ackermann_control is provided which reads AckermannDrive messages. You can find further documentation here.

Other Topics

Object information of other vehicles

Topic Type
/carla/objects derived_object_msgs.ObjectArray

Object information of all vehicles, except the ego-vehicle(s) is published.

Map

Topic Type
/carla/map std_msgs.String

The OPEN Drive map description is published.

Carla Ego Vehicle

carla_ego_vehicle provides a generic way to spawn an ego vehicle and attach sensors to it. You can find further documentation here.

Waypoint calculation

To make use of the Carla waypoint calculation a ROS Node is available to get waypoints. You can find further documentation here.

ROSBAG recording (not yet tested)

The carla_ros_bridge could also be used to record all published topics into a rosbag:

roslaunch carla_ros_bridge client_with_rviz.launch rosbag_fname:=/tmp/save_session.bag

This command will create a rosbag /tmp/save_session.bag

You can of course also use rosbag record to do the same, but using the ros_bridge to do the recording you have the guarentee that all the message are saved without small desynchronization that could occurs when using rosbag record in an other process.

Troubleshooting

ImportError: No module named carla

You're missing Carla Python. Please execute:

export PYTHONPATH=$PYTHONPATH:<path/to/carla/>/PythonAPI/<your_egg_file>

Please note that you have to put in the complete path to the egg-file including the egg-file itself. Please use the one, that is supported by your Python version. Depending on the type of CARLA (pre-build, or build from source), the egg files are typically located either directly in the PythonAPI folder or in PythonAPI/dist.

Check the installation is successfull by trying to import carla from python:

python -c 'import carla;print("Success")'

You should see the Success message without any errors.

ros-bridge's People

Contributors

fred-labs avatar fabianoboril avatar fpasch avatar berndgassmann avatar lgeo3 avatar togaen avatar danil-tolkachev avatar nsubiron avatar johannesquast avatar shepelilya avatar anshulpaigwar avatar sunpochin avatar atinfinity avatar thibault-buhet avatar

Watchers

James Cloos avatar

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.