Skip to content

Commit

Permalink
Merge pull request carla-simulator#2 from carla-simulator/master
Browse files Browse the repository at this point in the history
Update
  • Loading branch information
togaen authored Apr 5, 2019
2 parents e4eeac7 + 033e25e commit 041cd5e
Show file tree
Hide file tree
Showing 33 changed files with 1,452 additions and 37 deletions.
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
*.pyc
build.gradle
CMakeLists.txt
/CMakeLists.txt
.catkin_workspace
2 changes: 1 addition & 1 deletion .pylintrc
Original file line number Diff line number Diff line change
@@ -1,3 +1,3 @@
[TYPECHECK]
ignored-modules=numpy,carla
ignored-modules=numpy,carla,pygame
disable=logging-format-interpolation,locally-disabled,cyclic-import,too-many-instance-attributes,invalid-name
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
## Latest changed

* Add lane invasion sensor
* Add collision sensor
* Rename CarlaVehicleControl to CarlaEgoVehicleControl (and add some more message types)
* move PID controller into separate ROS node
Expand Down
85 changes: 56 additions & 29 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -27,37 +27,25 @@ This documentation is for CARLA versions *newer* than 0.9.4.

## Create a catkin workspace and install carla_ros_bridge package

First, clone or download the carla_ros_bridge, for example into

~/carla_ros_bridge
#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 ..

### Create the catkin workspace:
#install required ros-dependencies
rosdep update
rosdep install --from-path .

mkdir -p ~/ros/catkin_ws_for_carla/src
cd ~/ros/catkin_ws_for_carla/src
ln -s ~/carla_ros_bridge .
source /opt/ros/kinetic/setup.bash
#build
catkin_make
source ~/ros/catkin_ws_for_carla/devel/setup.bash

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

## Install the CARLA Python API

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.

# Start the ROS bridge

First run the simulator (see carla documentation: http://carla.readthedocs.io/en/latest/)
Expand All @@ -69,16 +57,20 @@ Wait for the message:

Waiting for the client to connect...

Then start the ros bridge:
Then start the ros bridge (choose one option):

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

To start the ros bridge with rviz use:
# Option 1: start the ros bridge
roslaunch carla_ros_bridge carla_ros_bridge.launch

source ~/ros/catkin_ws_for_carla/devel/setup.bash
# 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](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.
Expand Down Expand Up @@ -134,6 +126,12 @@ Currently the following sensors are supported:
|-------------------------------|------|
| `/carla/<ROLE NAME>/collision` | [carla_ros_bridge.CarlaCollisionEvent](carla_ros_bridge/msg/CarlaCollisionEvent.msg) |

#### Lane Invasion Sensor

|Topic | Type |
|-------------------------------|------|
| `/carla/<ROLE NAME>/lane_invasion` | [carla_ros_bridge.CarlaLaneInvasionEvent](carla_ros_bridge/msg/CarlaLaneInvasionEvent.msg) |

### Control

|Topic | Type |
Expand Down Expand Up @@ -185,6 +183,16 @@ Object information of all vehicles, except the ego-vehicle(s) is published.
The OPEN Drive map description is published.


# Example Ego Vehicle

An example Carla Client to spawn and control an ego vehicle is available. You can find further documentation [here](carla_ego_vehicle/README.md).


# Waypoint calculation

To make use of the Carla waypoint calculation a ROS Node is available to get waypoints. You can find further documentation [here](carla_waypoint_publisher/README.md).


# ROSBAG recording (not yet tested)

The carla_ros_bridge could also be used to record all published topics into a rosbag:
Expand All @@ -195,3 +203,22 @@ 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.
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
<!-- -->
<launch>
<arg name='host' default='localhost'/>
<arg name='port' default='2000'/>

<include file="$(find carla_ros_bridge)/launch/carla_ros_bridge.launch" pass_all_args="true"/>
<include file="$(find carla_ackermann_control)/launch/carla_ackermann_control.launch"/>
</launch>
24 changes: 24 additions & 0 deletions carla_ego_vehicle/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,24 @@
cmake_minimum_required(VERSION 2.8.3)
project(carla_ego_vehicle)

find_package(catkin REQUIRED COMPONENTS
rospy
)

catkin_python_setup()

catkin_package(
CATKIN_DEPENDS
rospy
)

catkin_install_python(PROGRAMS
src/carla_ego_vehicle/carla_example_ego_vehicle.py
src/carla_ego_vehicle/carla_ego_vehicle_base.py
src/carla_ego_vehicle/carla_ros_manual_control.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)
67 changes: 67 additions & 0 deletions carla_ego_vehicle/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,67 @@
# ROS Ego Vehicle

This package provides two ROS nodes:

- Carla Example Ego Vehicle: A reference client for spawning an ego vehicle
- Carla ROS Manual Control: a ROS-only manual control


## Carla Example Ego Vehicle

The reference Carla client `carla_example_ego_vehicle` can be used to spawn an ego vehicle (role-name: "ego_vehicle") with the following sensors attached to it.

- GNSS
- LIDAR
- Cameras (one front-camera + one camera for visualization in carla_ros_manual_control)
- Collision Sensor
- Lane Invasion Sensor

Info: To be able to use carla_ros_manual_control a camera with role-name 'view' is required.

If no specific position is set, the ego vehicle is spawned at a random position.


### Spawning at specific position

It is possible to (re)spawn the ego vehicle at the specific location by publishing to `/initialpose`.

The preferred way of doing that is using RVIZ:

![Autoware Runtime Manager Settings](../docs/images/rviz_set_start_goal.png)

Selecting a Pose with '2D Pose Estimate' will delete the current ego_vehicle and respawn it at the specified position.


### Create your own sensor setup

To setup your own ego vehicle with sensors, follow a similar approach as in `carla_example_ego_vehicle` by subclassing from `CarlaEgoVehicleBase`.

Define sensors with their attributes as described in the Carla Documentation about [Cameras and Sensors](https://github.com/carla-simulator/carla/blob/master/Docs/cameras_and_sensors.md).

The format is a list of dictionaries. One dictionary has the values as follows:

{
'type': '<SENSOR-TYPE>',
'role_name': '<NAME>',
'x': 0.0, 'y': 0.0, 'z': 0.0, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0, # pose of the sensor, relative to the vehicle
<ADDITIONAL-SENSOR-ATTRIBUTES>
}

## Carla ROS Manual Control

The node `carla_ros_manual_control` is a ROS-only version of the Carla `manual_control.py`. All data is received
via ROS topics.

Note: To be able to use carla_ros_manual_control a camera with role-name 'view' needs to be spawned by `carla_ego_vehicle`.


### Manual steering

In order to steer manually, you might need to disable sending vehicle control commands within another ROS node.

Therefore the manual control is able to publish to `/vehicle_control_manual_override` ([std_msgs/Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html)).

Press `B` to toggle the value.

Note: As sending the vehicle control commands is highly dependent on your setup, you need to implement the subscriber to that topic yourself.

13 changes: 13 additions & 0 deletions carla_ego_vehicle/launch/carla_example_ego_vehicle.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<!-- -->
<launch>
<arg name='host' default='localhost'/>
<arg name='port' default='2000'/>
<arg name="vehicle_filter" default="vehicle.*" />

<param name="/carla/host" value="$(arg host)" />
<param name="/carla/port" value="$(arg port)" />
<param name="/carla/client/vehicle_filter" value="$(arg vehicle_filter)" />

<node pkg="carla_ego_vehicle" type="carla_example_ego_vehicle.py" name="carla_example_ego_vehicle" output="screen"/>
</launch>

7 changes: 7 additions & 0 deletions carla_ego_vehicle/launch/carla_ros_manual_control.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<!-- -->
<launch>

<node pkg="carla_ego_vehicle" type="carla_ros_manual_control.py" name="carla_ros_manual_control" output="screen"/>

</launch>

14 changes: 14 additions & 0 deletions carla_ego_vehicle/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<?xml version="1.0"?>
<package format="2">
<name>carla_ego_vehicle</name>
<version>0.0.0</version>
<description>The carla_ego_vehicle package</description>
<maintainer email="[email protected]">CARLA Simulator Team</maintainer>
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>rospy</exec_depend>
<export>
</export>
</package>
10 changes: 10 additions & 0 deletions carla_ego_vehicle/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup(
packages=['carla_ego_vehicle'],
package_dir={'': 'src'}
)

setup(**d)

Empty file.
Loading

0 comments on commit 041cd5e

Please sign in to comment.