@@ -148,8 +148,13 @@ Now it is time to start running scripts. The following example will spawn some l
# Go to the folder containing example scripts
> cd PythonAPI/examples
-> python3 spawn_npc.py
+> python3 spawn_npc.py # Support for Python2 was provided until 0.9.10 (not included)
```
+
+!!! Note
+ The PythonAPI can be compiled for Python2 when using a [Linux build from source](build_linux.md).
+
+
#### Command-line options
There are some configuration options available when launching CARLA.
@@ -170,7 +175,7 @@ The script `PythonAPI/util/config.py` provides for more configuration options.
> ./config.py --map Town05 # Change map
> ./config.py --weather ClearNoon # Change weather
-> ./config.py --help # Check all the available configuration options.
+> ./config.py --help # Check all the available configuration options
```
---
diff --git a/Docs/tuto_A_add_map.md b/Docs/tuto_A_add_map.md
index 387fac0f7..e9a54d0b3 100644
--- a/Docs/tuto_A_add_map.md
+++ b/Docs/tuto_A_add_map.md
@@ -85,7 +85,7 @@ chmod 777 input_folder
__2. Run the script to cook the map.__ In the folder `~/carla/Util/Docker` there is a script that connects with the Docker image previously created, and makes the ingestion automatically. It only needs the path for the input and output files, and the name of the package to be ingested. If no `.json` is provided, the name must be `map_package`.
```sh
-python docker_tools.py --input ~/path_to_input_folder --output ~/path_to_output_folder --packages map_package
+python3 docker_tools.py --input ~/path_to_input_folder --output ~/path_to_output_folder --packages map_package
```
!!! Warning
If the argument `--package ` is not provided, the Docker will make a package of CARLA.
diff --git a/Docs/tuto_A_add_props.md b/Docs/tuto_A_add_props.md
index a7716dceb..c3af52f42 100644
--- a/Docs/tuto_A_add_props.md
+++ b/Docs/tuto_A_add_props.md
@@ -57,22 +57,30 @@ __Props__ need the following parameters.
* `medium`
* `big`
* `huge`
-* __tag__ value for the semantic segmentation. If the tag is misspelled, it will be read as `None`.
- * `None`
- * `Buildings`
- * `Fences`
- * `Pedestrians`
+* __tag__ value for the semantic segmentation. If the tag is misspelled, it will be read as `Unlabeled`.
+ * `Bridge`
+ * `Building`
+ * `Dynamic`
+ * `Fence`
+ * `Ground`
+ * `GuardRail`
+ * `Other`
+ * `Pedestrian`
* `Pole`
- * `Props`
* `RailTrack`
* `Road`
- * `RoadLines`
- * `Sidewalk`
+ * `RoadLine`
+ * `SideWalk`
+ * `Sky`
+ * `Static`
* `Terrain`
- * `TrafficSigns`
+ * `TrafficLight`
+ * `TrafficSign`
+ * `Unlabeled`
* `Vegetation`
* `Vehicles`
- * `Walls`
+ * `Wall`
+ * `Water`
In the end, the `.json` should look similar to the one below.
@@ -111,7 +119,7 @@ __1. Build a Docker image of Unreal Engine.__ Follow [these instructions](https:
__2. Run the script to cook the props.__ In the folder `~/carla/Util/Docker` there is a script that connects with the Docker image previously created, and makes the ingestion automatically. It only needs the path for the input and output files, and the name of the package to be ingested.
```sh
-python docker_tools.py --input ~/path_to_package --output ~/path_for_output_assets --package=Package01
+python3 docker_tools.py --input ~/path_to_package --output ~/path_for_output_assets --package=Package01
```
__3. Locate the package__. The Docker should have generated the package `Package01.tar.gz` in the output path. This is the standalone package for the assets.
diff --git a/Docs/tuto_A_add_vehicle.md b/Docs/tuto_A_add_vehicle.md
index d8bad3506..8c0d09e39 100644
--- a/Docs/tuto_A_add_vehicle.md
+++ b/Docs/tuto_A_add_vehicle.md
@@ -111,7 +111,7 @@ __4. Export the result__. Select all the meshes and the base of the skeleton a
* __11. Test the vehicle__. Launch CARLA, open a terminal in `PythonAPI/examples` and run the following command.
```sh
-python manual_control.py --filter # The name used in step 10.2
+python3 manual_control.py --filter # The name used in step 10.2
```
---
diff --git a/Docs/tuto_A_create_standalone.md b/Docs/tuto_A_create_standalone.md
index c60de808d..d4b8aca82 100644
--- a/Docs/tuto_A_create_standalone.md
+++ b/Docs/tuto_A_create_standalone.md
@@ -2,8 +2,8 @@
It is a common practice in CARLA to manage assets with standalone packages. Keeping them aside allows to reduce the size of the build. These asset packages can be easily imported into a CARLA package anytime. They also become really useful to easily distribute assets in an organized way.
-* [__Export a package from the UE4 Editor__](#export-a-package-from-the-ue4-editor)
-* [__Import assets into a CARLA package__](#import-assets-into-a-carla-package)
+* [__Export a package from the UE4 Editor__](#export-a-package-from-the-ue4-editor)
+* [__Import assets into a CARLA package__](#import-assets-into-a-carla-package)
---
## Export a package from the UE4 Editor
diff --git a/Docs/tuto_A_vehicle_modelling.md b/Docs/tuto_A_vehicle_modelling.md
index 6ba949ce8..06d536dca 100644
--- a/Docs/tuto_A_vehicle_modelling.md
+++ b/Docs/tuto_A_vehicle_modelling.md
@@ -1,9 +1,16 @@
# How to model vehicles
+* [__4-wheeled Vehicles__](#4-wheeled-vehicles)
+ * [Modelling](#modelling)
+ * [Naming materials](#naming-materials)
+ * [Texturing](#texturing)
+ * [Rigging](#rigging)
+ * [LODs](#lods)
+
---
## 4-Wheeled Vehicles
-#### Modelling
+### Modelling
Vehicles must have a minimum of 10.000 and a maximum of 17.000 Tris
approximately. We model the vehicles using the size and scale of actual cars.
@@ -36,7 +43,7 @@ The vehicle must be divided in 6 materials:
Put a rectangular plane with this size 29-12 cm, for the licence Plate.
We assign the license plate texture.
-#### Nomenclature of Material
+### Naming materials
* M(Material)_"CarName"_Bodywork(part of car)
@@ -50,7 +57,7 @@ The vehicle must be divided in 6 materials:
* M_"CarName"_LicencePlate
-#### Textures
+### Texturing
The size of the textures is 2048x2048.
@@ -71,7 +78,7 @@ TEXTURES
MATERIAL
* M_Tesla3_BodyWork
-#### RIG
+### Rigging
The easiest way is to copy the "General4WheeledVehicleSkeleton" present in our project,
either by exporting it and copying it to your model or by creating your skeleton
diff --git a/Docs/tuto_D_create_sensor.md b/Docs/tuto_D_create_sensor.md
index e28c395f6..de49031d8 100644
--- a/Docs/tuto_D_create_sensor.md
+++ b/Docs/tuto_D_create_sensor.md
@@ -5,6 +5,19 @@ the necessary steps to implement a sensor in Unreal Engine 4 (UE4) and expose
its data via CARLA's Python API. We'll follow all the steps by creating a new
sensor as an example.
+* [__Prerequisites__](#prerequisites)
+* [__Introduction__](#introduction)
+* [__Creating a new sensor__](#creating-a-new-sensor)
+ * [1- Sensor actor](#1-sensor-actor)
+ * [2- Sensor data serializer](#2-sensor-data-serializer)
+ * [3- Sensor data object](#3-sensor-data-object)
+ * [4- Register your sensor](#4-register-your-sensor)
+ * [5- Usage example](#5-usage-example)
+* [__Appendix__](#appendix)
+ * [Reusing buffers](#reusing-buffers)
+ * [Sending data asynchronously](#sending-data-asynchronously)
+ * [Client-side sensors](#client-side-sensors)
+
---
## Prerequisites
@@ -71,8 +84,7 @@ _For the sake of simplicity we're not going to take into account all the edge
cases, nor it will be implemented in the most efficient way. This is just an
illustrative example._
----
-### 1. The sensor actor
+### 1- Sensor actor
This is the most complicated class we're going to create. Here we're running
inside Unreal Engine framework, knowledge of UE4 API will be very helpful but
@@ -295,8 +307,7 @@ that, the data is going to travel through several layers. First of them will be
the serializer that we have to create next. We'll fully understand this part
once we have completed the `Serialize` function in the next section.
----
-### 2. The sensor data serializer
+### 2- Sensor data serializer
This class is actually rather simple, it's only required to have two static
methods, `Serialize` and `Deserialize`. We'll add two files for it, this time to
@@ -365,8 +376,8 @@ SharedPtr SafeDistanceSerializer::Deserialize(RawData &&data) {
except for the fact that we haven't defined yet what's a `SafeDistanceEvent`.
----
-### 3. The sensor data object
+
+### 3- Sensor data object
We need to create a data object for the users of this sensor, representing the
data of a _safe distance event_. We'll add this file to
@@ -431,8 +442,7 @@ What we're doing here is exposing some C++ methods in Python. Just with this,
the Python API will be able to recognise our new event and it'll behave similar
to an array in Python, except that cannot be modified.
----
-### 4. Register your sensor
+### 4- Register your sensor
Now that the pipeline is complete, we're ready to register our new sensor. We do
so in _LibCarla/source/carla/sensor/SensorRegistry.h_. Follow the instruction in
@@ -454,8 +464,7 @@ be a bit cryptic.
make rebuild
```
----
-### 5. Usage example
+### 5- Usage example
Finally, we have the sensor included and we have finished recompiling, our
sensor by now should be available in Python.
@@ -493,7 +502,9 @@ Vehicle too close: vehicle.mercedes-benz.coupe
That's it, we have a new sensor working!
---
-## Appendix: Reusing buffers
+## Appendix
+
+### Reusing buffers
In order to optimize memory usage, we can use the fact that each sensor sends
buffers of similar size; in particularly, in the case of cameras, the size of
@@ -530,8 +541,7 @@ buffer.reset(512u); // (size 512 bytes, capacity 1024 bytes)
buffer.reset(2048u); // (size 2048 bytes, capacity 2048 bytes) -> allocates
```
----
-## Appendix: Sending data asynchronously
+### Sending data asynchronously
Some sensors may require to send data asynchronously, either for performance or
because the data is generated in a different thread, for instance, camera sensors send
@@ -554,8 +564,7 @@ void MySensor::Tick(float DeltaSeconds)
}
```
----
-## Appendix: Client-side sensors
+### Client-side sensors
Some sensors do not require the simulator to do their measurements, those
sensors may run completely in the client-side freeing the simulator from extra
diff --git a/Docs/tuto_D_customize_vehicle_suspension.md b/Docs/tuto_D_customize_vehicle_suspension.md
new file mode 100644
index 000000000..deec87efc
--- /dev/null
+++ b/Docs/tuto_D_customize_vehicle_suspension.md
@@ -0,0 +1,237 @@
+# Customize vehicle suspension
+
+This tutorial covers the basics of the suspension system for CARLA vehicles, and how are these implemented for the different vehicles available. Use this information to access the suspension parameterization of a vehicle in Unreal Engine, and customize it at will.
+
+* [__Basics of the suspension system__](#basics-of-the-suspension-system)
+* [__Suspension groups__](#suspension-groups)
+ * [Coupe](#coupe)
+ * [Off-road](#off-road)
+ * [Truck](#truck)
+ * [Urban](#urban)
+ * [Van](#van)
+
+---
+## Basics of the suspension system
+
+The suspension system of a vehicle is defined by the wheels of said vehicle. Each wheel has an independent blueprint with some parameterization, which includes the suspension system.
+
+These blueprints can be found in `Content/Carla/Blueprints/Vehicles/`. They are named such as: `BP__W`.
+
+* `F` or `R` is used for front or rear wheels correspondingly.
+* `R` or `L` is used for right or left wheels correspondingly.
+
+![tuto_suspension_blueprints](img/tuto_suspension_blueprints.jpg)
+In this example, the blueprint of the front left wheel of the Audi A2 is named as BP_AudiA2_FLW
.
+
+`shape_radius` for the wheel to rest over the road, neither hovering nor inside of it.
+
+Inside the blueprint, there is a section with some parameterization regarding the suspension of the wheel. Here are their definitions as described in Unreal Engine.
+
+* `Suspension Force Offset` — Vertical offset from where suspension forces are applied (along Z axis).
+* `Suspension Max Raise` — How far the wheel can go above the resting position.
+* `Suspension Max Drop` — How far the wheel can drop below the resting position.
+* `Suspension Natural Frequency` — Oscillation frequency of the suspension. Standard cars have values between `5` and `10`.
+* `Suspension Damping Ratio` — The rate at which energy is dissipated from the spring. Standard cars have values between `0.8` and `1.2`. Values `<1` are more sluggish, values `>1` are more twitchy.
+* `Sweep Type` — Wether wheel suspension considers simple, complex or both.
+
+![tuto_suspension_parameterization](img/tuto_suspension_parameterization.jpg)
+The Suspension panel inside a wheel blueprint.
+
+!!! Note
+ By default, all the wheels of a vehicle have the same parameterization in CARLA. The following explanations will be covered per vehicle, instead of per wheel.
+
+---
+## Suspension groups
+
+According to their system suspension, vehicles in CARLA can be classified in five groups. All the vehicles in a group have the same parameterization, as they are expected to have a similar behaviour on the road. The suspension of a vehicle can be modified at will, and is no subject to these five groups. However understanding these, and observing their behaviour in the simulation can be of great use to define a custom suspension.
+
+The five groups are: *Coupe*, *Off-road*, *Truck*, *Urban*, and *Van*. In closer observation, the parameterization of these groups follows a specific pattern.
+
+
+
+Stiff suspension |
+Coupe |
+Urban |
+Van |
+Off-road |
+Truck |
+Soft suspension |
+
+
+
+
+When moving from a soft to a stiff suspension, there are some clear tendencies in the parameterization.
+
+* __Decrease__ of `Suspension Max Raise` and `Suspension Max Drop` — Stiff vehicles are meant to drive over plane roads with no bumps. For the sake of aerodynamics, the chassis is not supposed to move greatly, but remain constantly close to the ground.
+* __Increase__ of `Suspension Damping Ratio` — The absortion of the bouncing by the dampers is greater for stiff vehicles.
+
+### Coupe
+
+Vehicles with the stiffest suspension.
+
+
+
+Parameterization |
+Vehicles |
+
+
+
+Suspension Force Offset — 0.0
+Suspension Max Raise — 7.5
+Suspension Max Drop — 7.5
+Suspension Natural Frequency — 9.5
+Suspension Damping Ratio — 1.0
+Sweep Type — SimpleAndComplex
+ |
+
+vehicle.audi.tt
+vehicle.lincoln.mkz2017
+vehicle.mercedes-benz.coupe
+vehicle.seat.leon
+vehicle.tesla.model3
+ |
+
+
+
+
+### Off-road
+
+Vehicles with a soft suspension.
+
+
+
+Parameterization |
+Vehicles |
+
+
+
+Suspension Force Offset — 0.0
+Suspension Max Raise — 15.0
+Suspension Max Drop — 15.0
+Suspension Natural Frequency — 7.0
+Suspension Damping Ratio — 0.5
+Sweep Type — SimpleAndComplex
+ |
+
+vehicle.audi.etron
+vehicle.jeep.wrangler_rubicon
+vehicle.nissan.patrol
+vehicle.tesla.cybertruck
+ |
+
+
+
+
+
+### Truck
+
+Vehicles with the softest suspension.
+
+
+
+Parameterization |
+Vehicles |
+
+
+
+Suspension Force Offset — 0.0
+Suspension Max Raise — 17.0
+Suspension Max Drop — 17.0
+Suspension Natural Frequency — 6.0
+Suspension Damping Ratio — 0.4
+Sweep Type — SimpleAndComplex
+ |
+
+vehicle.carlamotors.carlacola
+ |
+
+
+
+
+
+### Urban
+
+Vehicles with a soft suspension.
+
+
+
+Parameterization |
+Vehicles |
+
+
+
+Suspension Force Offset — 0.0
+Suspension Max Raise — 8.0
+Suspension Max Drop — 8.0
+Suspension Natural Frequency — 9.0
+Suspension Damping Ratio — 0.8
+Sweep Type — SimpleAndComplex
+ |
+
+vehicle.audi.a2
+vehicle.bmw.grandtourer
+vehicle.chevrolet.impala
+vehicle.citroen.c3
+vehicle.dodge_charger.police
+vehicle.mini.cooperst
+vehicle.mustang.mustang
+vehicle.nissan.micra
+vehicle.toyota.prius
+ |
+
+
+
+
+### Van
+
+Vehicles with a middle-ground suspension.
+
+
+
+Parameterization |
+Vehicles |
+
+
+
+Suspension Force Offset — 0.0
+Suspension Max Raise — 9.0
+Suspension Max Drop — 9.0
+Suspension Natural Frequency — 8.0
+Suspension Damping Ratio — 0.8
+Sweep Type — SimpleAndComplex
+ |
+
+vehicle.volkswagen.t2
+ |
+
+
+
+
+
+---
+
+Use the forum to post any doubts, issues or suggestions regarding this topic.
+
+
+
+Here are some advised readings after this one.
+
+
diff --git a/Docs/tuto_D_generate_pedestrian_navigation.md b/Docs/tuto_D_generate_pedestrian_navigation.md
index 3b3b45919..603f5edca 100644
--- a/Docs/tuto_D_generate_pedestrian_navigation.md
+++ b/Docs/tuto_D_generate_pedestrian_navigation.md
@@ -1,8 +1,5 @@
# How to generate the pedestrian navigation info
----
-## Introduction
-
The pedestrians to walk need information about the map in a specific format. That file that describes the map for navigation is a binary file with extension `.BIN`, and they are saved in the **Nav** folder of the map. Each map needs a `.BIN` file with the same name that the map, so automatically can be loaded with the map.
This `.BIN` file is generated from the Recast & Detour library and has all the information that allows pathfinding and crow management.
@@ -18,13 +15,34 @@ If we need to generate this `.BIN` file for a custom map, we need to follow this
We have several types of meshes for navigation. The meshes need to be identified as one of those types, using specific nomenclature.
-| Type | Start with | Description |
-|-----------|------------|-------------|
-| Ground | `Road_Sidewalk` | Pedestrians can walk over these meshes freely (sidewalks...). |
-| Grass | `Road_Crosswalk` | Pedestrians can walk over these meshes but as a second option if no ground is found. |
-| Road | `Road_Grass` | Pedestrians won't be allowed to walk on it unless we specify some percentage of pedestrians that will be allowed. |
-| Crosswalk | `Road_Road`, `Road_Curb`, `Road_Gutter` or `Road_Marking` | Pedestrians can cross the roads only through these meshes. |
-| Block | any other name | Pedestrians will avoid these meshes always (are obstacles like traffic lights, trees, houses...). |
+
+
+Type |
+Start with |
+Description |
+
+
+Ground |
+Road_Sidewalk |
+Pedestrians can walk over these meshes freely (sidewalks...). |
+
+Grass |
+Road_Crosswalk |
+Pedestrians can walk over these meshes but as a second option if no ground is found. |
+
+Road |
+Road_Grass |
+Pedestrians won't be allowed to walk on it unless we specify some percentage of pedestrians that will be allowed. |
+
+Crosswalk |
+Road_Road , Road_Curb , Road_Gutter , Road_Marking |
+Pedestrians can cross the roads only through these meshes. |
+
+Block |
+Any other name |
+Pedestrians will avoid these meshes always (are obstacles like traffic lights, trees, houses...). |
+
+
diff --git a/Docs/tuto_G_control_walker_skeletons.md b/Docs/tuto_G_control_walker_skeletons.md
index 39bc39a2d..afa17bcc0 100644
--- a/Docs/tuto_G_control_walker_skeletons.md
+++ b/Docs/tuto_G_control_walker_skeletons.md
@@ -5,6 +5,12 @@ skeletons of walkers from the CARLA Python API. The reference of
all classes and methods available can be found at
[Python API reference](python_api.md).
+* [__Walker skeleton structure__](#walker-skeleton-structure)
+* [__Manually control walker bones__](#manually-control-walker-bones)
+ * [Connect to the simulator](#connect-to-the-simulator)
+ * [Spawn a walker](#spawn-a-walker)
+ * [Control walker skeletons](#control-walker-skeletons)
+
!!! note
**This document assumes the user is familiar with the Python API**.
The user should read the first steps tutorial before reading this document.
@@ -86,12 +92,12 @@ crl_root
```
---
-## How to manually control a walker's bones
+## Manually control walker bones
Following is a detailed step-by-step example of how to change the bone transforms of a walker
from the CARLA Python API
-#### Connecting to the simulator
+### Connect to the simulator
Import neccessary libraries used in this example
@@ -107,7 +113,7 @@ client = carla.Client('127.0.0.1', 2000)
client.set_timeout(2.0)
```
-#### Spawning a walker
+### Spawn a walker
Spawn a random walker at one of the map's spawn points
@@ -119,7 +125,7 @@ spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform()
world.try_spawn_actor(blueprint, spawn_point)
```
-#### Controlling a walker's skeleton
+### Control walker skeletons
A walker's skeleton can be modified by passing an instance of the WalkerBoneControl class
to the walker's apply_control function. The WalkerBoneControl class contains the transforms
diff --git a/Docs/tuto_G_openstreetmap.md b/Docs/tuto_G_openstreetmap.md
index ebfd49471..eb6a4d9a9 100644
--- a/Docs/tuto_G_openstreetmap.md
+++ b/Docs/tuto_G_openstreetmap.md
@@ -91,15 +91,18 @@ world = client.generate_opendrive_world(
__b) Using `config.py`__ — The script can load an OpenStreetMap file directly into CARLA using a new argument.
```
-config.py --osm-file=/path/to/OSM/file
+python3 config.py --osm-file=/path/to/OSM/file
```
-!!! Warning
+!!! Important
[client.generate_opendrive_world()](python_api.md#carla.Client.generate_opendrive_world) requires the __content of the OpenDRIVE file parsed as string__, and allows parameterization. On the contrary, __`config.py`__ script needs __the path to the `.xodr` file__ and always uses default parameters.
Either way, the map should be ingested automatically in CARLA and the result should be similar to this.
![opendrive_meshissue](img/tuto_g_osm_carla.jpg)
Outcome of the CARLA map generation using OpenStreetMap.
+!!! Warning
+ The roads generated end abruptly in the borders of the map. This will cause the TM to crash when vehicles are not able to find the next waypoint. To avoid this, the OSM mode is set to __True__ by default ([set_osm_mode()](python_api.md#carlatrafficmanager)). This will show a warning, and destroy vehicles when necessary.
+
---
That is all there is to know about how to use OpenStreetMap to generate CARLA maps.
diff --git a/Docs/tuto_G_retrieve_data.md b/Docs/tuto_G_retrieve_data.md
index 95581fbef..be168678b 100644
--- a/Docs/tuto_G_retrieve_data.md
+++ b/Docs/tuto_G_retrieve_data.md
@@ -4,39 +4,39 @@ Learning an efficient way to retrieve simulation data is essential in CARLA. Thi
First, the simulation is initialized with custom settings and traffic. An ego vehicle is set to roam around the city, optionally with some basic sensors. The simulation is recorded, so that later it can be queried to find the highlights. After that, the original simulation is played back, and exploited to the limit. New sensors can be added to retrieve consistent data. The weather conditions can be changed. The recorder can even be used to test specific scenarios with different outputs.
-* [__Overview__](#overview)
-* [__Set the simulation__](#set-the-simulation)
- * [Map setting](#map-setting)
- * [Weather setting](#weather-setting)
-* [__Set traffic__](#set-traffic)
- * [CARLA traffic and pedestrians](#carla-traffic-and-pedestrians)
- * [SUMO co-simulation traffic](#sumo-co-simulation-traffic)
-* [__Set the ego vehicle__](#set-the-ego-vehicle)
- * [Spawn the ego vehicle](#spawn-the-ego-vehicle)
- * [Place the spectator](#place-the-spectator)
-* [__Set basic sensors__](#set-basic-sensors)
- * [RGB camera](#rgb-camera)
- * [Detectors](#detectors)
- * [Other sensors](#other-sensors)
-* [__Set advanced sensors__](#set-advanced-sensors)
- * [Depth camera](#depth-camera)
- * [Semantic segmentation camera](#semantic-segmentation-camera)
- * [LIDAR raycast sensor](#lidar-raycast-sensor)
- * [Radar sensor](#radar-sensor)
-* [__No-rendering-mode__](#no-rendering-mode)
- * [Simulate at a fast pace](#simulate-at-a-fast-pace)
- * [Manual control without rendering](#manual-control-without-rendering)
-* [__Record and retrieve data__](#record-and-retrieve-data)
- * [Start recording](#start-recording)
- * [Capture and record](#capture-and-record)
- * [Stop recording](#stop-recording)
-* [__Exploit the recording__](#exploit-the-recording)
- * [Query the events](#query-the-events)
- * [Choose a fragment](#choose-a-fragment)
- * [Retrieve more data](#retrieve-more-data)
- * [Change the weather](#change-the-weather)
- * [Try new outcomes](#try-new-outcomes)
-* [__Tutorial scripts__](#tutorial-scripts)
+* [__Overview__](#overview)
+* [__Set the simulation__](#set-the-simulation)
+ * [Map setting](#map-setting)
+ * [Weather setting](#weather-setting)
+* [__Set traffic__](#set-traffic)
+ * [CARLA traffic and pedestrians](#carla-traffic-and-pedestrians)
+ * [SUMO co-simulation traffic](#sumo-co-simulation-traffic)
+* [__Set the ego vehicle__](#set-the-ego-vehicle)
+ * [Spawn the ego vehicle](#spawn-the-ego-vehicle)
+ * [Place the spectator](#place-the-spectator)
+* [__Set basic sensors__](#set-basic-sensors)
+ * [RGB camera](#rgb-camera)
+ * [Detectors](#detectors)
+ * [Other sensors](#other-sensors)
+* [__Set advanced sensors__](#set-advanced-sensors)
+ * [Depth camera](#depth-camera)
+ * [Semantic segmentation camera](#semantic-segmentation-camera)
+ * [LIDAR raycast sensor](#lidar-raycast-sensor)
+ * [Radar sensor](#radar-sensor)
+* [__No-rendering-mode__](#no-rendering-mode)
+ * [Simulate at a fast pace](#simulate-at-a-fast-pace)
+ * [Manual control without rendering](#manual-control-without-rendering)
+* [__Record and retrieve data__](#record-and-retrieve-data)
+ * [Start recording](#start-recording)
+ * [Capture and record](#capture-and-record)
+ * [Stop recording](#stop-recording)
+* [__Exploit the recording__](#exploit-the-recording)
+ * [Query the events](#query-the-events)
+ * [Choose a fragment](#choose-a-fragment)
+ * [Retrieve more data](#retrieve-more-data)
+ * [Change the weather](#change-the-weather)
+ * [Try new outcomes](#try-new-outcomes)
+* [__Tutorial scripts__](#tutorial-scripts)
---
## Overview
@@ -87,7 +87,7 @@ Open a new terminal. Change the map using the __config.py__ script.
```
cd /opt/carla/PythonAPI/utils
-./config.py --map Town01
+python3 config.py --map Town01
```
This script can enable different settings. Some of them will be mentioned during the tutorial, others will not. Hereunder there is a brief summary.
@@ -133,14 +133,14 @@ Each town is loaded with a specific weather that fits it, however this can be se
```sh
cd /opt/carla/PythonAPI/examples
-python dynamic_weather.py --speed 1.0
+python3 dynamic_weather.py --speed 1.0
```
* __To set custom conditions__. Use the script __environment.py__. There are quite a lot of possible settings. Take a look at the optional arguments, and the documentation for [carla.WeatherParameters](python_api.md#carla.WeatherParameters).
```sh
cd /opt/carla/PythonAPI/util
-python environment.py --clouds 100 --rain 80 --wetness 100 --puddles 60 --wind 80 --fog 50
+python3 environment.py --clouds 100 --rain 80 --wetness 100 --puddles 60 --wind 80 --fog 50
```
@@ -182,7 +182,7 @@ Open a new terminal, and run __spawn_npc.py__ to spawn vehicles and walkers. Let
```sh
cd /opt/carla/PythonAPI/examples
-python spawn_npc.py -n 50 -w 50 --safe
+python3 spawn_npc.py -n 50 -w 50 --safe
```
Optional arguments in spawn_npc.py
@@ -228,7 +228,7 @@ echo "export SUMO_HOME=/usr/share/sumo" >> ~/.bashrc && source ~/.bashrc
* With the CARLA server on, run the [SUMO-CARLA synchrony script](https://github.com/carla-simulator/carla/blob/master/Co-Simulation/Sumo/run_synchronization.py).
```sh
cd ~/carla/Co-Simulation/Sumo
-python run_synchronization.py examples/Town01.sumocfg --sumo-gui
+python3 run_synchronization.py examples/Town01.sumocfg --sumo-gui
```
* A SUMO window should have opened. __Press Play__ in order to start traffic in both simulations.
```
@@ -632,7 +632,7 @@ The same `config.py` used to [set the map](#map-setting) can disable rendering,
```
cd /opt/carla/PythonAPI/utils
-./config.py --no-rendering --delta-seconds 0.05 # Never greater than 0.1s
+python3 config.py --no-rendering --delta-seconds 0.05 # Never greater than 0.1s
```
!!! Warning
@@ -644,12 +644,12 @@ The script `PythonAPI/examples/no_rendering_mode.py` provides an overview of the
```
cd /opt/carla/PythonAPI/examples
-python manual_control.py
+python3 manual_control.py
```
```
cd /opt/carla/PythonAPI/examples
-python no_rendering_mode.py --no-rendering
+python3 no_rendering_mode.py --no-rendering
```
@@ -712,7 +712,7 @@ while True:
```
cd /opt/carla/PythonAPI/examples
-python manual_control.py
+python3 manual_control.py
```
!!! Note
@@ -742,7 +742,7 @@ It is time to run a new simulation.
To reenact the simulation, [choose a fragment](#choose-a-fragment) and run the script containing the code for the playback.
```sh
-python tuto_replay.py
+python3 tuto_replay.py
```
### Query the events
diff --git a/Jenkinsfile b/Jenkinsfile
index 0c4c788b8..17f3036ab 100644
--- a/Jenkinsfile
+++ b/Jenkinsfile
@@ -43,7 +43,7 @@ pipeline
{
steps
{
- sh 'make setup ARGS="--python3-version=3.7"'
+ sh 'make setup ARGS="--python-version=3.7"'
}
}
stage('ubuntu build')
@@ -51,7 +51,7 @@ pipeline
steps
{
sh 'make LibCarla'
- sh 'make PythonAPI ARGS="--python3-version=3.7"'
+ sh 'make PythonAPI ARGS="--python-version=3.7"'
sh 'make CarlaUE4Editor'
sh 'make examples'
}
@@ -68,7 +68,7 @@ pipeline
{
steps
{
- sh 'make check ARGS="--all --xml --python3-version=3.7"'
+ sh 'make check ARGS="--all --xml --python-version=3.7"'
}
post
{
@@ -90,8 +90,8 @@ pipeline
{
steps
{
- sh 'make package ARGS="--python3-version=3.7"'
- sh 'make package ARGS="--packages=AdditionalMaps --clean-intermediate --python3-version=3.7"'
+ sh 'make package ARGS="--python-version=3.7"'
+ sh 'make package ARGS="--packages=AdditionalMaps --clean-intermediate --python-version=3.7"'
sh 'make examples ARGS="localhost 3654"'
}
post
@@ -102,9 +102,64 @@ pipeline
stash includes: 'Dist/CARLA*.tar.gz', name: 'ubuntu_package'
stash includes: 'Examples/', name: 'ubuntu_examples'
}
+ success
+ {
+ node('master')
+ {
+ script
+ {
+ JOB_ID = "${env.BUILD_TAG}"
+ jenkinsLib = load("/home/jenkins/jenkins.groovy")
+
+ jenkinsLib.CreateUbuntuTestNode(JOB_ID)
+ }
+ }
+ }
}
}
- stage('ubuntu deploy')
+ stage('ubuntu smoke tests')
+ {
+ agent { label "ubuntu && gpu && ${JOB_ID}" }
+ steps
+ {
+ unstash name: 'ubuntu_eggs'
+ unstash name: 'ubuntu_package'
+ unstash name: 'ubuntu_examples'
+ sh 'tar -xvzf Dist/CARLA*.tar.gz -C Dist/'
+ sh 'DISPLAY= ./Dist/CarlaUE4.sh -opengl --carla-rpc-port=3654 --carla-streaming-port=0 -nosound > CarlaUE4.log &'
+ sh 'make smoke_tests ARGS="--xml --python-version=3.7"'
+ sh 'make run-examples ARGS="localhost 3654"'
+ }
+ post
+ {
+ always
+ {
+ archiveArtifacts 'CarlaUE4.log'
+ junit 'Build/test-results/smoke-tests-*.xml'
+ deleteDir()
+ node('master')
+ {
+ script
+ {
+ JOB_ID = "${env.BUILD_TAG}"
+ jenkinsLib = load("/home/jenkins/jenkins.groovy")
+
+ jenkinsLib.DeleteUbuntuTestNode(JOB_ID)
+ }
+ }
+ }
+ }
+ }
+ stage('ubuntu deploy dev')
+ {
+ when { branch "dev"; }
+ steps
+ {
+ sh 'git checkout .'
+ sh 'make deploy ARGS="--replace-latest"'
+ }
+ }
+ stage('ubuntu deploy master')
{
when { anyOf { branch "master"; buildingTag() } }
steps
@@ -121,6 +176,7 @@ pipeline
sh 'rm -rf ~/carla-simulator.github.io/Doxygen'
sh '''
cd ~/carla-simulator.github.io
+ git remote set-url origin git@github.com:carla-simulator/carla-simulator.github.io.git
git fetch
git checkout -B master origin/master
'''
@@ -237,7 +293,7 @@ pipeline
}
stage('windows deploy')
{
- when { anyOf { branch "master"; buildingTag() } }
+ when { anyOf { branch "master"; branch "dev"; buildingTag() } }
steps {
bat """
call ../setEnv64.bat
diff --git a/LibCarla/cmake/client/CMakeLists.txt b/LibCarla/cmake/client/CMakeLists.txt
index c0b9de355..ee7fabf2c 100644
--- a/LibCarla/cmake/client/CMakeLists.txt
+++ b/LibCarla/cmake/client/CMakeLists.txt
@@ -75,6 +75,11 @@ if (WIN32)
# Install zlib lib.
file(GLOB libpng_libraries "${LIBPNG_LIB_PATH}/*")
install(FILES ${libpng_libraries} DESTINATION lib)
+else ()
+ # Install libpng library
+ install(DIRECTORY "${LIBPNG_INCLUDE_PATH}" DESTINATION include/system)
+ file(GLOB libcarla_carla_libpnglib "${LIBPNG_LIB_PATH}/*.*")
+ install(FILES ${libcarla_carla_libpnglib} DESTINATION lib)
endif (WIN32)
# Add sources.
@@ -257,7 +262,8 @@ if (LIBCARLA_BUILD_RELEASE)
target_include_directories(carla_client${carla_target_postfix} SYSTEM PRIVATE
"${BOOST_INCLUDE_PATH}"
"${RPCLIB_INCLUDE_PATH}"
- "${RECAST_INCLUDE_PATH}")
+ "${RECAST_INCLUDE_PATH}"
+ "${LIBPNG_INCLUDE_PATH}")
if (BUILD_RSS_VARIANT)
target_compile_definitions(carla_client${carla_target_postfix} PRIVATE RSS_ENABLED RSS_USE_TBB)
@@ -296,7 +302,8 @@ if (LIBCARLA_BUILD_DEBUG)
target_include_directories(carla_client${carla_target_postfix}_debug SYSTEM PRIVATE
"${BOOST_INCLUDE_PATH}"
"${RPCLIB_INCLUDE_PATH}"
- "${RECAST_INCLUDE_PATH}")
+ "${RECAST_INCLUDE_PATH}"
+ "${LIBPNG_INCLUDE_PATH}")
if (BUILD_RSS_VARIANT)
target_compile_definitions(carla_client${carla_target_postfix}_debug PRIVATE RSS_ENABLED RSS_USE_TBB)
diff --git a/LibCarla/cmake/test/CMakeLists.txt b/LibCarla/cmake/test/CMakeLists.txt
index d2ac1ddf1..432f509e7 100644
--- a/LibCarla/cmake/test/CMakeLists.txt
+++ b/LibCarla/cmake/test/CMakeLists.txt
@@ -48,7 +48,8 @@ foreach(target ${build_targets})
target_include_directories(${target} SYSTEM PRIVATE
"${BOOST_INCLUDE_PATH}"
"${RPCLIB_INCLUDE_PATH}"
- "${GTEST_INCLUDE_PATH}")
+ "${GTEST_INCLUDE_PATH}"
+ "${LIBPNG_INCLUDE_PATH}")
target_include_directories(${target} PRIVATE
"${libcarla_source_path}/test")
diff --git a/LibCarla/source/carla/ThreadPool.h b/LibCarla/source/carla/ThreadPool.h
index c9cc38567..b807d4e24 100644
--- a/LibCarla/source/carla/ThreadPool.h
+++ b/LibCarla/source/carla/ThreadPool.h
@@ -12,6 +12,7 @@
#include "carla/Time.h"
#include
+#include
#include
#include
@@ -40,7 +41,7 @@ namespace carla {
std::future Post(FunctorT &&functor) {
auto task = std::packaged_task(std::forward(functor));
auto future = task.get_future();
- _io_context.post(carla::MoveHandler(task));
+ boost::asio::post(_io_context, carla::MoveHandler(task));
return future;
}
diff --git a/LibCarla/source/carla/client/Actor.cpp b/LibCarla/source/carla/client/Actor.cpp
index aee967280..476d51890 100644
--- a/LibCarla/source/carla/client/Actor.cpp
+++ b/LibCarla/source/carla/client/Actor.cpp
@@ -40,22 +40,46 @@ namespace client {
GetEpisode().Lock()->SetActorTransform(*this, transform);
}
- void Actor::SetVelocity(const geom::Vector3D &vector) {
- GetEpisode().Lock()->SetActorVelocity(*this, vector);
+ void Actor::SetTargetVelocity(const geom::Vector3D &vector) {
+ GetEpisode().Lock()->SetActorTargetVelocity(*this, vector);
}
- void Actor::SetAngularVelocity(const geom::Vector3D &vector) {
- GetEpisode().Lock()->SetActorAngularVelocity(*this, vector);
+ void Actor::SetTargetAngularVelocity(const geom::Vector3D &vector) {
+ GetEpisode().Lock()->SetActorTargetAngularVelocity(*this, vector);
}
- void Actor::AddImpulse(const geom::Vector3D &vector) {
- GetEpisode().Lock()->AddActorImpulse(*this, vector);
+ void Actor::EnableConstantVelocity(const geom::Vector3D &vector) {
+ GetEpisode().Lock()->EnableActorConstantVelocity(*this, vector);
+ }
+
+ void Actor::DisableConstantVelocity() {
+ GetEpisode().Lock()->DisableActorConstantVelocity(*this);
+ }
+
+ void Actor::AddImpulse(const geom::Vector3D &impulse) {
+ GetEpisode().Lock()->AddActorImpulse(*this, impulse);
+ }
+
+ void Actor::AddImpulse(const geom::Vector3D &impulse, const geom::Vector3D &location) {
+ GetEpisode().Lock()->AddActorImpulse(*this, impulse, location);
+ }
+
+ void Actor::AddForce(const geom::Vector3D &force) {
+ GetEpisode().Lock()->AddActorForce(*this, force);
+ }
+
+ void Actor::AddForce(const geom::Vector3D &force, const geom::Vector3D &location) {
+ GetEpisode().Lock()->AddActorForce(*this, force, location);
}
void Actor::AddAngularImpulse(const geom::Vector3D &vector) {
GetEpisode().Lock()->AddActorAngularImpulse(*this, vector);
}
+ void Actor::AddTorque(const geom::Vector3D &torque) {
+ GetEpisode().Lock()->AddActorTorque(*this, torque);
+ }
+
void Actor::SetSimulatePhysics(const bool enabled) {
GetEpisode().Lock()->SetActorSimulatePhysics(*this, enabled);
}
diff --git a/LibCarla/source/carla/client/Actor.h b/LibCarla/source/carla/client/Actor.h
index 03f66b71d..3710765bb 100644
--- a/LibCarla/source/carla/client/Actor.h
+++ b/LibCarla/source/carla/client/Actor.h
@@ -64,18 +64,36 @@ namespace client {
/// Teleport and rotate the actor to @a transform.
void SetTransform(const geom::Transform &transform);
- /// Set the actor velocity.
- void SetVelocity(const geom::Vector3D &vector);
+ /// Set the actor velocity before applying physics.
+ void SetTargetVelocity(const geom::Vector3D &vector);
- /// Set the angular velocity of the actor
- void SetAngularVelocity(const geom::Vector3D &vector);
+ /// Set the angular velocity of the actor before applying physics.
+ void SetTargetAngularVelocity(const geom::Vector3D &vector);
- /// Add impulse to the actor.
+ /// Enable a constant velocity mode
+ void EnableConstantVelocity(const geom::Vector3D &vector);
+
+ /// Disable the constant velocity mode
+ void DisableConstantVelocity();
+
+ /// Add impulse to the actor at its center of mass.
void AddImpulse(const geom::Vector3D &vector);
+ /// Add impulse to the actor at certain location.
+ void AddImpulse(const geom::Vector3D &impulse, const geom::Vector3D &location);
+
+ /// Add force to the actor at its center of mass.
+ void AddForce(const geom::Vector3D &force);
+
+ /// Add force to the actor at certain location.
+ void AddForce(const geom::Vector3D &force, const geom::Vector3D &location);
+
/// Add angular impulse to the actor.
void AddAngularImpulse(const geom::Vector3D &vector);
+ /// Add a torque to the actor.
+ void AddTorque(const geom::Vector3D &vector);
+
/// Enable or disable physics simulation on this actor.
void SetSimulatePhysics(bool enabled = true);
diff --git a/LibCarla/source/carla/client/LaneInvasionSensor.cpp b/LibCarla/source/carla/client/LaneInvasionSensor.cpp
index ffff730b2..30c48f8b6 100644
--- a/LibCarla/source/carla/client/LaneInvasionSensor.cpp
+++ b/LibCarla/source/carla/client/LaneInvasionSensor.cpp
@@ -151,8 +151,7 @@ namespace client {
}
auto episode = GetEpisode().Lock();
- SharedPtr