diff --git a/Docs/Example.CarlaSettings.ini b/Docs/Example.CarlaSettings.ini
index 87a18dd66..bdfd63835 100644
--- a/Docs/Example.CarlaSettings.ini
+++ b/Docs/Example.CarlaSettings.ini
@@ -73,10 +73,10 @@ ImageSizeX=800
ImageSizeY=600
; Camera (horizontal) field of view in degrees.
FOV=90
-; Position of the camera relative to the car in centimeters.
-PositionX=15
+; Position of the camera relative to the car in meters.
+PositionX=0.20
PositionY=0
-PositionZ=123
+PositionZ=1.30
; Rotation of the camera relative to the car in degrees.
RotationPitch=8
RotationRoll=0
@@ -93,8 +93,8 @@ PostProcessing=Depth
SensorType=LIDAR_RAY_TRACE
; Number of lasers.
Channels=32
-; Measure distance in centimeters.
-Range=5000
+; Measure distance in meters.
+Range=50.0
; Points generated by all lasers per second.
PointsPerSecond=100000
; Lidar rotation frequency.
@@ -105,7 +105,7 @@ LowerFOVLimit=-30
; Position and rotation relative to the vehicle.
PositionX=0
PositionY=0
-PositionZ=140
+PositionZ=1.40
RotationPitch=0
RotationYaw=0
RotationRoll=0
diff --git a/Docs/cameras_and_sensors.md b/Docs/cameras_and_sensors.md
index 4bd2c9d4f..45ce66f07 100644
--- a/Docs/cameras_and_sensors.md
+++ b/Docs/cameras_and_sensors.md
@@ -1,6 +1,10 @@
Cameras and sensors
===================
+!!! important
+ Since version 0.8.0 the positions of the sensors are specified in meters
+ instead of centimeters. Always relative to the vehicle.
+
Cameras and sensors can be added to the player vehicle by defining them in the
settings sent by the client on every new episode. This can be done either by
filling a `CarlaSettings` Python class ([client_example.py][clientexamplelink])
@@ -39,7 +43,7 @@ using the functions at `carla.image_converter` Python module.
Camera: Scene final
-------------------
-![SceneFinal](img/capture_scenefinal.png)
+![SceneFinal](img/capture_scenefinal.png)
The "scene final" camera provides a view of the scene after applying some
post-processing effects to create a more realistic feel. These are actually
@@ -61,7 +65,7 @@ in the Camera. We use the following post process effects:
camera = carla.sensor.Camera('MyCamera', PostProcessing='SceneFinal')
camera.set(FOV=90.0)
camera.set_image_size(800, 600)
-camera.set_position(x=30, y=0, z=130)
+camera.set_position(x=0.30, y=0, z=1.30)
camera.set_rotation(pitch=0, yaw=0, roll=0)
carla_settings.add_sensor(camera)
@@ -76,9 +80,9 @@ PostProcessing=SceneFinal
ImageSizeX=800
ImageSizeY=600
FOV=90
-PositionX=30
+PositionX=0.30
PositionY=0
-PositionZ=130
+PositionZ=1.30
RotationPitch=0
RotationRoll=0
RotationYaw=0
@@ -122,7 +126,7 @@ seen in "PythonClient/point_cloud_example.py".
camera = carla.sensor.Camera('MyCamera', PostProcessing='Depth')
camera.set(FOV=90.0)
camera.set_image_size(800, 600)
-camera.set_position(x=30, y=0, z=130)
+camera.set_position(x=0.30, y=0, z=1.30)
camera.set_rotation(pitch=0, yaw=0, roll=0)
carla_settings.add_sensor(camera)
@@ -137,9 +141,9 @@ PostProcessing=Depth
ImageSizeX=800
ImageSizeY=600
FOV=90
-PositionX=30
+PositionX=0.30
PositionY=0
-PositionZ=130
+PositionZ=1.30
RotationPitch=0
RotationRoll=0
RotationYaw=0
@@ -192,7 +196,7 @@ _"Unreal/CarlaUE4/Content/Static/Pedestrians"_ folder it's tagged as pedestrian.
camera = carla.sensor.Camera('MyCamera', PostProcessing='SemanticSegmentation')
camera.set(FOV=90.0)
camera.set_image_size(800, 600)
-camera.set_position(x=30, y=0, z=130)
+camera.set_position(x=0.30, y=0, z=1.30)
camera.set_rotation(pitch=0, yaw=0, roll=0)
carla_settings.add_sensor(camera)
@@ -207,9 +211,9 @@ PostProcessing=SemanticSegmentation
ImageSizeX=800
ImageSizeY=600
FOV=90
-PositionX=30
+PositionX=0.30
PositionY=0
-PositionZ=130
+PositionZ=1.30
RotationPitch=0
RotationRoll=0
RotationYaw=0
@@ -234,10 +238,10 @@ The received `LidarMeasurement` object contains the following information
Key | Type | Description
-------------------------- | ---------- | ------------
-horizontal_angle | float | Angle in XY plane of the lidar this frame
-channels | uint32 | Number of channels (lasers) of the lidar
-point_count_by_channel | uint32 | Number of points per channel captured this frame
-point_cloud | PointCloud | Captured points this frame
+horizontal_angle | float | Angle in XY plane of the lidar this frame (in degrees).
+channels | uint32 | Number of channels (lasers) of the lidar.
+point_count_by_channel | uint32 | Number of points per channel captured this frame.
+point_cloud | PointCloud | Captured points this frame.
###### Python
@@ -245,12 +249,12 @@ point_cloud | PointCloud | Captured points this frame
lidar = carla.sensor.Lidar('MyLidar')
lidar.set(
Channels=32,
- Range=5000,
+ Range=50,
PointsPerSecond=100000,
RotationFrequency=10,
UpperFovLimit=10,
LowerFovLimit=-30)
-lidar.set_position(x=0, y=0, z=140)
+lidar.set_position(x=0, y=0, z=1.40)
lidar.set_rotation(pitch=0, yaw=0, roll=0)
carla_settings.add_sensor(lidar)
@@ -262,14 +266,14 @@ carla_settings.add_sensor(lidar)
[CARLA/Sensor/MyLidar]
SensorType=LIDAR_RAY_TRACE
Channels=32
-Range=5000
+Range=50
PointsPerSecond=100000
RotationFrequency=10
UpperFOVLimit=10
LowerFOVLimit=-30
PositionX=0
PositionY=0
-PositionZ=140
+PositionZ=1.40
RotationPitch=0
RotationYaw=0
RotationRoll=0
diff --git a/Docs/img/Road_Instructions_Example.png b/Docs/img/road_instructions_example.png
similarity index 100%
rename from Docs/img/Road_Instructions_Example.png
rename to Docs/img/road_instructions_example.png
diff --git a/Docs/img/steering_angle_mustang.png b/Docs/img/steering_angle_mustang.png
new file mode 100644
index 000000000..2ac4eab18
Binary files /dev/null and b/Docs/img/steering_angle_mustang.png differ
diff --git a/Docs/map_customization.md b/Docs/map_customization.md
index a242dd427..ce029721f 100644
--- a/Docs/map_customization.md
+++ b/Docs/map_customization.md
@@ -22,7 +22,7 @@
- You can change the seed until you have a map you are satisfied with.
- After that you can place new PlayerStarts at the places you want the cars to be spawned.
- The AI already works, but the cars won't act randomly. Vehicles will follow the instructions given by the RoadMapGenerator. They will follow the road easily while in straight roads but wont so much when entering Intersections:
-![Road_Instructions_Example.png](img/Road_Instructions_Example.png)
+![road_instructions_example.png](img/road_instructions_example.png)
> (This is a debug view of the instructions the road gives to the Vehicle. They will always follow the green arrows, the white points are shared points between one or more routes, by default they order the vehicle to continue straight; Black points are off the road, the vehicle gets no instructions and drives to the left, trying to get back to the road)
- To get a random behavior, you have to place IntersectionEntrances, this will let you redefine the direction the vehicle will take overwriting the directions given by the road map (until they finish their given order).
diff --git a/Docs/measurements.md b/Docs/measurements.md
index 59b39b51c..bff877e03 100644
--- a/Docs/measurements.md
+++ b/Docs/measurements.md
@@ -1,6 +1,11 @@
Measurements
============
+!!! important
+ Since version 0.8.0 the measurements received by the client are in SI
+ units. All locations have been converted to `meters` and speeds to
+ `meters/second`.
+
Every frame the server sends a package with the measurements and images gathered
to the client. This document describes the details of these measurements.
@@ -10,10 +15,10 @@ Time-stamps
Since CARLA can be run at fixed-frame rate, we keep track of two different
time-stamps.
-Key | Type | Description
--------------------------- | --------- | ------------
-platform_timestamp | uint32 | Time-stamp of the current frame, in milliseconds as given by the OS.
-game_timestamp | uint32 | In-game time-stamp, milliseconds elapsed since the beginning of the current level.
+Key | Type | Units | Description
+-------------------------- | --------- | ------------ | ------------
+platform_timestamp | uint32 | milliseconds | Time-stamp of the current frame, as given by the OS.
+game_timestamp | uint32 | milliseconds | In-game time-stamp, elapsed since the beginning of the current level.
In real-time mode, the elapsed time between two time steps should be similar
both platform and game time-stamps. When run in fixed-time step, the game
@@ -23,27 +28,27 @@ time-stamp keeps the actual time elapsed.
Player measurements
-------------------
-Key | Type | Description
--------------------------- | --------- | ------------
-transform | Transform | World transform of the player.
-acceleration | Vector3D | Current acceleration of the player.
-forward_speed | float | Forward speed in km/h.
-collision_vehicles | float | Collision intensity with other vehicles.
-collision_pedestrians | float | Collision intensity with pedestrians.
-collision_other | float | General collision intensity (everything else but pedestrians and vehicles).
-intersection_otherlane | float | Percentage of the car invading other lanes.
-intersection_offroad | float | Percentage of the car off-road.
-autopilot_control | Control | Vehicle's autopilot control that would apply this frame.
+Key | Type | Units | Description
+-------------------------- | --------- | ------ | ------------
+transform | Transform | | World transform of the player (contains a locations and a rotation).
+acceleration | Vector3D | m/s^2 | Current acceleration of the player.
+forward_speed | float | m/s | Forward speed of the player.
+collision_vehicles | float | kg*m/s | Collision intensity with other vehicles.
+collision_pedestrians | float | kg*m/s | Collision intensity with pedestrians.
+collision_other | float | kg*m/s | General collision intensity (everything else but pedestrians and vehicles).
+intersection_otherlane | float | | Percentage of the car invading other lanes.
+intersection_offroad | float | | Percentage of the car off-road.
+autopilot_control | Control | | Vehicle's autopilot control that would apply this frame.
###### Transform
The transform contains the location and rotation of the player.
-Key | Type | Description
--------------------------- | ---------- | ------------
-location | Vector3D | World location.
-orientation *[deprecated]* | Vector3D | Orientation in Cartesian coordinates.
-rotation | Rotation3D | Pitch, roll, and yaw.
+Key | Type | Units | Description
+-------------------------- | ---------- | ------- | ------------
+location | Vector3D | m | World location.
+orientation *[deprecated]* | Vector3D | | Orientation in Cartesian coordinates.
+rotation | Rotation3D | degrees | Pitch, roll, and yaw.
###### Collision
@@ -100,6 +105,8 @@ carla_client.send_control(control)
has a maximum steering angle of 70 degrees (this can be checked in the vehicle's
front wheel blueprint).
+![Mustan Steering Angle](img/steering_angle_mustang.png)
+
Non-player agents info
----------------------
diff --git a/PythonClient/carla/benchmarks/benchmark.py b/PythonClient/carla/benchmarks/benchmark.py
index 2e6f3a164..18d96b7b5 100644
--- a/PythonClient/carla/benchmarks/benchmark.py
+++ b/PythonClient/carla/benchmarks/benchmark.py
@@ -119,8 +119,8 @@ class Benchmark(object):
image.save_to_disk(self._image_filename_format.format(
episode_name, name, frame))
- curr_x = measurements.player_measurements.transform.location.x
- curr_y = measurements.player_measurements.transform.location.y
+ curr_x = 1e2 * measurements.player_measurements.transform.location.x
+ curr_y = 1e2 * measurements.player_measurements.transform.location.y
measurement_vec.append(measurements.player_measurements)
diff --git a/PythonClient/carla/benchmarks/corl_2017.py b/PythonClient/carla/benchmarks/corl_2017.py
index 5989ee1d2..f005c1e70 100644
--- a/PythonClient/carla/benchmarks/corl_2017.py
+++ b/PythonClient/carla/benchmarks/corl_2017.py
@@ -142,7 +142,7 @@ class CoRL2017(Benchmark):
camera.set_image_size(800, 600)
- camera.set_position(200, 0, 140)
+ camera.set_position(2.0, 0.0, 1.4)
camera.set_rotation(-15.0, 0, 0)
weathers = [1, 3, 6, 8, 4, 14]
diff --git a/PythonClient/carla/image_converter.py b/PythonClient/carla/image_converter.py
index 2b3b44491..b75ed3d22 100644
--- a/PythonClient/carla/image_converter.py
+++ b/PythonClient/carla/image_converter.py
@@ -114,7 +114,7 @@ def depth_to_local_point_cloud(image, color=None, max_depth=0.9):
RGB color of an array.
"max_depth" is used to omit the points that are far enough.
"""
- far = 100000.0 # max depth in centimeters
+ far = 1000.0 # max depth in meters.
normalized_depth = depth_to_array(image)
# (Intrinsic) K Matrix
diff --git a/PythonClient/carla/planner/converter.py b/PythonClient/carla/planner/converter.py
index d33c8bada..0f683c457 100644
--- a/PythonClient/carla/planner/converter.py
+++ b/PythonClient/carla/planner/converter.py
@@ -137,6 +137,7 @@ class Converter(object):
"""
rotation = np.array([world[0], world[1], world[2]])
+ rotation *= 1e2 # meters to centimeters.
rotation = rotation.dot(self._worldrotation)
relative_location = [rotation[0] + self._worldoffset[0] - self._mapoffset[0],
diff --git a/PythonClient/carla/sensor.py b/PythonClient/carla/sensor.py
index 2a09cb019..aa073145b 100644
--- a/PythonClient/carla/sensor.py
+++ b/PythonClient/carla/sensor.py
@@ -49,9 +49,9 @@ class Sensor(object):
def __init__(self, name, sensor_type):
self.SensorName = name
self.SensorType = sensor_type
- self.PositionX = 140.0
+ self.PositionX = 0.2
self.PositionY = 0.0
- self.PositionZ = 140.0
+ self.PositionZ = 1.3
self.RotationPitch = 0.0
self.RotationRoll = 0.0
self.RotationYaw = 0.0
diff --git a/PythonClient/client_example.py b/PythonClient/client_example.py
index 4270199ff..37b01da5f 100755
--- a/PythonClient/client_example.py
+++ b/PythonClient/client_example.py
@@ -60,19 +60,19 @@ def run_carla_client(args):
camera0 = Camera('CameraRGB')
# Set image resolution in pixels.
camera0.set_image_size(800, 600)
- # Set its position relative to the car in centimeters.
- camera0.set_position(30, 0, 130)
+ # Set its position relative to the car in meters.
+ camera0.set_position(0.30, 0, 1.30)
settings.add_sensor(camera0)
# Let's add another camera producing ground-truth depth.
camera1 = Camera('CameraDepth', PostProcessing='Depth')
camera1.set_image_size(800, 600)
- camera1.set_position(30, 0, 130)
+ camera1.set_position(0.30, 0, 1.30)
settings.add_sensor(camera1)
if args.lidar:
lidar = Lidar('Lidar32')
- lidar.set_position(0, 0, 250)
+ lidar.set_position(0, 0, 2.50)
lidar.set_rotation(0, 0, 0)
lidar.set(
Channels=32,
@@ -158,14 +158,14 @@ def print_measurements(measurements):
number_of_agents = len(measurements.non_player_agents)
player_measurements = measurements.player_measurements
message = 'Vehicle at ({pos_x:.1f}, {pos_y:.1f}), '
- message += '{speed:.2f} km/h, '
+ message += '{speed:.0f} km/h, '
message += 'Collision: {{vehicles={col_cars:.0f}, pedestrians={col_ped:.0f}, other={col_other:.0f}}}, '
message += '{other_lane:.0f}% other lane, {offroad:.0f}% off-road, '
message += '({agents_num:d} non-player agents in the scene)'
message = message.format(
- pos_x=player_measurements.transform.location.x / 100, # cm -> m
- pos_y=player_measurements.transform.location.y / 100,
- speed=player_measurements.forward_speed,
+ pos_x=player_measurements.transform.location.x,
+ pos_y=player_measurements.transform.location.y,
+ speed=player_measurements.forward_speed * 3.6, # m/s -> km/h
col_cars=player_measurements.collision_vehicles,
col_ped=player_measurements.collision_pedestrians,
col_other=player_measurements.collision_other,
diff --git a/PythonClient/manual_control.py b/PythonClient/manual_control.py
index 8b285159a..7f03b6cc4 100755
--- a/PythonClient/manual_control.py
+++ b/PythonClient/manual_control.py
@@ -19,6 +19,7 @@ Use ARROWS or WASD keys for control.
AD : steer
Q : toggle reverse
Space : hand-brake
+ P : toggle autopilot
R : restart level
@@ -41,6 +42,7 @@ try:
from pygame.locals import K_UP
from pygame.locals import K_a
from pygame.locals import K_d
+ from pygame.locals import K_p
from pygame.locals import K_q
from pygame.locals import K_r
from pygame.locals import K_s
@@ -80,22 +82,22 @@ def make_carla_settings(enable_lidar):
settings.randomize_seeds()
camera0 = sensor.Camera('CameraRGB')
camera0.set_image_size(WINDOW_WIDTH, WINDOW_HEIGHT)
- camera0.set_position(200, 0, 140)
+ camera0.set_position(2.0, 0.0, 1.4)
camera0.set_rotation(0.0, 0.0, 0.0)
settings.add_sensor(camera0)
camera1 = sensor.Camera('CameraDepth', PostProcessing='Depth')
camera1.set_image_size(MINI_WINDOW_WIDTH, MINI_WINDOW_HEIGHT)
- camera1.set_position(200, 0, 140)
+ camera1.set_position(2.0, 0.0, 1.4)
camera1.set_rotation(0.0, 0.0, 0.0)
settings.add_sensor(camera1)
camera2 = sensor.Camera('CameraSemSeg', PostProcessing='SemanticSegmentation')
camera2.set_image_size(MINI_WINDOW_WIDTH, MINI_WINDOW_HEIGHT)
- camera2.set_position(200, 0, 140)
+ camera2.set_position(2.0, 0.0, 1.4)
camera2.set_rotation(0.0, 0.0, 0.0)
settings.add_sensor(camera2)
if enable_lidar:
lidar = sensor.Lidar('Lidar32')
- lidar.set_position(0, 0, 250)
+ lidar.set_position(0, 0, 2.5)
lidar.set_rotation(0, 0, 0)
lidar.set(
Channels=32,
@@ -129,13 +131,14 @@ class Timer(object):
class CarlaGame(object):
- def __init__(self, carla_client, enable_lidar=False, city_name=None):
+ def __init__(self, carla_client, enable_autopilot=False, enable_lidar=False, city_name=None):
self.client = carla_client
self._timer = None
self._display = None
self._main_image = None
self._mini_view_image1 = None
self._mini_view_image2 = None
+ self._enable_autopilot = enable_autopilot
self._enable_lidar = enable_lidar
self._lidar_measurement = None
self._map_view = None
@@ -230,6 +233,8 @@ class CarlaGame(object):
if control is None:
self._on_new_episode()
+ elif self._enable_autopilot:
+ self.client.send_control(measurements.player_measurements.autopilot_control)
else:
self.client.send_control(control)
@@ -253,6 +258,8 @@ class CarlaGame(object):
control.hand_brake = True
if keys[K_q]:
self._is_on_reverse = not self._is_on_reverse
+ if keys[K_p]:
+ self._enable_autopilot = not self._enable_autopilot
control.reverse = self._is_on_reverse
return control
@@ -273,7 +280,7 @@ class CarlaGame(object):
ori_y=lane_orientation[1],
step=self._timer.step,
fps=self._timer.ticks_per_second(),
- speed=player_measurements.forward_speed,
+ speed=player_measurements.forward_speed * 3.6,
other_lane=100 * player_measurements.intersection_otherlane,
offroad=100 * player_measurements.intersection_offroad)
print_over_same_line(message)
@@ -285,7 +292,7 @@ class CarlaGame(object):
message = message.format(
step=self._timer.step,
fps=self._timer.ticks_per_second(),
- speed=player_measurements.forward_speed,
+ speed=player_measurements.forward_speed * 3.6,
other_lane=100 * player_measurements.intersection_otherlane,
offroad=100 * player_measurements.intersection_offroad)
print_over_same_line(message)
@@ -375,6 +382,10 @@ def main():
default=2000,
type=int,
help='TCP port to listen to (default: 2000)')
+ argparser.add_argument(
+ '-a', '--autopilot',
+ action='store_true',
+ help='enable autopilot')
argparser.add_argument(
'-l', '--lidar',
action='store_true',
@@ -398,7 +409,7 @@ def main():
try:
with make_carla_client(args.host, args.port) as client:
- game = CarlaGame(client, args.lidar, args.map_name)
+ game = CarlaGame(client, args.autopilot, args.lidar, args.map_name)
game.execute()
break
diff --git a/PythonClient/point_cloud_example.py b/PythonClient/point_cloud_example.py
index 50c53867c..65bef0d65 100755
--- a/PythonClient/point_cloud_example.py
+++ b/PythonClient/point_cloud_example.py
@@ -33,7 +33,7 @@ def run_carla_client(host, port, far):
frame_step = 100 # Save one image every 100 frames
output_folder = '_out'
image_size = [800, 600]
- camera_local_pos = [30, 0, 130] # [X, Y, Z]
+ camera_local_pos = [0.3, 0.0, 1.3] # [X, Y, Z]
camera_local_rotation = [0, 0, 0] # [pitch(Y), yaw(Z), roll(X)]
fov = 70
diff --git a/Unreal/CarlaUE4/Config/DefaultGame.ini b/Unreal/CarlaUE4/Config/DefaultGame.ini
index 1ec4936fc..1e25447a2 100644
--- a/Unreal/CarlaUE4/Config/DefaultGame.ini
+++ b/Unreal/CarlaUE4/Config/DefaultGame.ini
@@ -33,6 +33,7 @@ bEncryptIniFiles=False
bSkipEditorContent=False
+MapsToCook=(FilePath="/Game/Maps/Town01")
+MapsToCook=(FilePath="/Game/Maps/Town02")
++DirectoriesToAlwaysCook=(Path="Static/GenericMaterials/Licenseplates/Textures")
bNativizeBlueprintAssets=False
bNativizeOnlySelectedBlueprints=False
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp
index 5a918eb29..553816786 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp
@@ -17,7 +17,7 @@ UWalkerAgentComponent::UWalkerAgentComponent(const FObjectInitializer &ObjectIni
float UWalkerAgentComponent::GetForwardSpeed() const
{
/// @todo Is it necessary to compute this speed every tick?
- return FVector::DotProduct(Walker->GetVelocity(), Walker->GetActorRotation().Vector()) * 0.036f;
+ return FVector::DotProduct(Walker->GetVelocity(), Walker->GetActorRotation().Vector());
}
void UWalkerAgentComponent::BeginPlay()
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h
index 7b1ead9b7..111b41d37 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h
@@ -23,7 +23,7 @@ public:
UWalkerAgentComponent(const FObjectInitializer &ObjectInitializer);
- /// Return forward speed in km/h.
+ /// Return forward speed in cm/s.
float GetForwardSpeed() const;
FVector GetBoundingBoxExtent() const
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp
index b2484286d..c41eafac7 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaHUD.cpp
@@ -69,18 +69,21 @@ static FText GetHUDText(const ACarlaPlayerState &Vehicle)
HighPrecision.MinimumFractionalDigits = 2u;
HighPrecision.MaximumFractionalDigits = 2u;
+ constexpr float TO_METERS = 1e-2;
+ constexpr float TO_KMPH = 0.036f;
+
FFormatNamedArguments Args;
Args.Add("FPS", RoundedFloatAsText(Vehicle.GetFramesPerSecond()));
- Args.Add("Location", GetVectorAsText(Vehicle.GetLocation()));
- Args.Add("Acceleration", GetVectorAsText(Vehicle.GetAcceleration(), HighPrecision));
+ Args.Add("Location", GetVectorAsText(Vehicle.GetLocation() * TO_METERS));
+ Args.Add("Acceleration", GetVectorAsText(Vehicle.GetAcceleration() * TO_METERS, HighPrecision));
Args.Add("Orientation", GetVectorAsText(Vehicle.GetOrientation(), HighPrecision));
- Args.Add("Speed", RoundedFloatAsText(Vehicle.GetForwardSpeed()));
+ Args.Add("Speed", RoundedFloatAsText(Vehicle.GetForwardSpeed() * TO_KMPH));
Args.Add("Gear", GetGearAsText(Vehicle.GetCurrentGear()));
Args.Add("SpeedLimit", RoundedFloatAsText(Vehicle.GetSpeedLimit()));
Args.Add("TrafficLightState", GetTrafficLightAsText(Vehicle.GetTrafficLightState()));
- Args.Add("CollisionCars", RoundedFloatAsText(Vehicle.GetCollisionIntensityCars()));
- Args.Add("CollisionPedestrians", RoundedFloatAsText(Vehicle.GetCollisionIntensityPedestrians()));
- Args.Add("CollisionOther", RoundedFloatAsText(Vehicle.GetCollisionIntensityOther()));
+ Args.Add("CollisionCars", RoundedFloatAsText(Vehicle.GetCollisionIntensityCars() * TO_METERS));
+ Args.Add("CollisionPedestrians", RoundedFloatAsText(Vehicle.GetCollisionIntensityPedestrians() * TO_METERS));
+ Args.Add("CollisionOther", RoundedFloatAsText(Vehicle.GetCollisionIntensityOther() * TO_METERS));
Args.Add("IntersectionOtherLane", RoundedFloatAsText(100.0f * Vehicle.GetOtherLaneIntersectionFactor()));
Args.Add("IntersectionOffRoad", RoundedFloatAsText(100.0f * Vehicle.GetOffRoadIntersectionFactor()));
return FText::Format(
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp
index 8a98acab3..4c5cde58a 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp
@@ -19,7 +19,6 @@
#include "Paths.h"
-
static constexpr auto DEPTH_MAT_PATH =
#if PLATFORM_LINUX
TEXT("Material'/Carla/PostProcessingMaterials/DepthEffectMaterial_GLSL.DepthEffectMaterial_GLSL'");
@@ -142,14 +141,14 @@ void ASceneCaptureCamera::BeginPlay()
void ASceneCaptureCamera::Tick(const float DeltaSeconds)
{
Super::Tick(DeltaSeconds);
- auto fn = [=](){WritePixels(DeltaSeconds);};
+ auto fn = [=](FRHICommandListImmediate& RHICmdList){WritePixels(DeltaSeconds,RHICmdList);};
ENQUEUE_UNIQUE_RENDER_COMMAND_ONEPARAMETER(
FWritePixels,
decltype(fn),write_function,fn,
{
- write_function();
+ write_function(RHICmdList);
});
-
+
}
float ASceneCaptureCamera::GetFOVAngle() const
@@ -226,7 +225,7 @@ bool ASceneCaptureCamera::ReadPixels(TArray &BitMap) const
return RTResource->ReadPixels(BitMap, ReadPixelFlags);
}
-void ASceneCaptureCamera::WritePixels(float DeltaTime) const
+void ASceneCaptureCamera::WritePixels(float DeltaTime, FRHICommandListImmediate& rhi_cmd_list) const
{
check(IsInRenderingThread());
if(!CaptureRenderTarget)
@@ -234,16 +233,8 @@ void ASceneCaptureCamera::WritePixels(float DeltaTime) const
UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target"));
return ;
}
- FRHITexture2D *texture = CaptureRenderTarget->GetRenderTargetResource()->GetRenderTargetTexture();
- if(!texture)
- {
- UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render texture"));
- return ;
- }
- const uint32 width = texture->GetSizeX();
- uint32 height = texture->GetSizeY();
- uint32 stride;
- uint8 *src = reinterpret_cast(RHILockTexture2D(texture, 0, RLM_ReadOnly, stride, false));
+ FTextureRenderTarget2DResource* RenderResource = (FTextureRenderTarget2DResource*)CaptureRenderTarget->Resource;
+
struct {
uint32 Width;
uint32 Height;
@@ -255,31 +246,56 @@ void ASceneCaptureCamera::WritePixels(float DeltaTime) const
PostProcessEffect::ToUInt(PostProcessEffect),
CaptureComponent2D->FOVAngle
};
- FSensorDataView DataView(
- GetId(),
- FReadOnlyBufferView{reinterpret_cast(&ImageHeader), sizeof(ImageHeader)},
- FReadOnlyBufferView{src,stride*height}
- );
- WriteSensorData(DataView);
-
- /*
- * example of buffer manual copy
- const uint32 bufferSize = stride * height;
- RawData.Empty(width*height);
- FMemory::BigBlockMemcpy(captureBuffer->getBuffer(), src, captureBuffer->getBufferSize());
- for(unsigned y = 0; y < height; ++y)
+ if(IsVulkanPlatform(GMaxRHIShaderPlatform))
{
- for(unsigned x = 0; x < width; ++x)
- {
- //RGBA ->
- RawData.Add(FColor(src[2],src[1],src[0],src[3]));
- src += 4;
- }
- }*/
-
- RHIUnlockTexture2D(texture, 0, false);
-
+ FTextureRHIParamRef texture = RenderResource->GetRenderTargetTexture();
+ if(!texture)
+ {
+ UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target texture"));
+ return;
+ }
+ struct FReadSurfaceContext
+ {
+ FRenderTarget* SrcRenderTarget;
+ TArray* OutData;
+ FIntRect Rect;
+ FReadSurfaceDataFlags Flags;
+ };
+ TArray Pixels;
+ rhi_cmd_list.ReadSurfaceData(
+ texture,
+ FIntRect(0, 0, RenderResource->GetSizeXY().X, RenderResource->GetSizeXY().Y),
+ Pixels,
+ FReadSurfaceDataFlags(RCM_UNorm, CubeFace_MAX)
+ );
+ FSensorDataView DataView(
+ GetId(),
+ FReadOnlyBufferView{reinterpret_cast(&ImageHeader), sizeof(ImageHeader)},
+ FReadOnlyBufferView{Pixels}
+ );
+ WriteSensorData(DataView);
+ } else
+ {
+ //if it's not vulkan we can lock the render target texture resource
+ FRHITexture2D *texture = CaptureRenderTarget->GetRenderTargetResource()->GetRenderTargetTexture();
+ if(!texture)
+ {
+ UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render texture"));
+ return ;
+ }
+ const uint32 height = texture->GetSizeY();
+ uint32 stride;
+ uint8 *src = reinterpret_cast(RHILockTexture2D(texture, 0, RLM_ReadOnly, stride, false));
+ const FSensorDataView DataView(
+ GetId(),
+ FReadOnlyBufferView{reinterpret_cast(&ImageHeader), sizeof(ImageHeader)},
+ FReadOnlyBufferView{src,stride*height}
+ );
+
+ WriteSensorData(DataView);
+ RHIUnlockTexture2D(texture, 0, false);
+ }
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h
index 3fb87e633..6e1f3fcd8 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h
@@ -72,7 +72,7 @@ public:
private:
///Read the camera buffer and write it to a color array
- void WritePixels(float DeltaTime) const;
+ void WritePixels(float DeltaTime,FRHICommandListImmediate& rhi_cmd_list) const;
/// Used to synchronize the DrawFrustumComponent with the
/// SceneCaptureComponent2D settings.
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp
index c3c66550b..1cf710b8a 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp
@@ -17,6 +17,9 @@
#include
+// Conversion from centimeters to meters.
+static constexpr float TO_METERS = 1e-2;
+
// =============================================================================
// -- Static local methods -----------------------------------------------------
// =============================================================================
@@ -47,7 +50,7 @@ static void Encode(const FRotator &Rotator, carla_rotation3d &Data)
static void Encode(const FTransform &Transform, carla_transform &Data)
{
- Encode(Transform.GetLocation(), Data.location);
+ Encode(Transform.GetLocation() * TO_METERS, Data.location);
Encode(Transform.GetRotation().GetForwardVector(), Data.orientation);
Encode(Transform.Rotator(), Data.rotation);
}
@@ -107,12 +110,12 @@ void FCarlaEncoder::Encode(
Data.game_timestamp = PlayerState.GetGameTimeStamp();
auto &Player = Data.player_measurements;
::Encode(PlayerState.GetTransform(), Player.transform);
- ::Encode(PlayerState.GetBoundsExtent(), Player.box_extent);
- ::Encode(PlayerState.GetAcceleration(), Player.acceleration);
- Player.forward_speed = PlayerState.GetForwardSpeed();
- Player.collision_vehicles = PlayerState.GetCollisionIntensityCars();
- Player.collision_pedestrians = PlayerState.GetCollisionIntensityPedestrians();
- Player.collision_other = PlayerState.GetCollisionIntensityOther();
+ ::Encode(PlayerState.GetBoundsExtent() * TO_METERS, Player.box_extent);
+ ::Encode(PlayerState.GetAcceleration() * TO_METERS, Player.acceleration);
+ Player.forward_speed = PlayerState.GetForwardSpeed() * TO_METERS;
+ Player.collision_vehicles = PlayerState.GetCollisionIntensityCars() * TO_METERS;
+ Player.collision_pedestrians = PlayerState.GetCollisionIntensityPedestrians() * TO_METERS;
+ Player.collision_other = PlayerState.GetCollisionIntensityOther() * TO_METERS;
Player.intersection_otherlane = PlayerState.GetOtherLaneIntersectionFactor();
Player.intersection_offroad = PlayerState.GetOffRoadIntersectionFactor();
Player.autopilot_control.steer = PlayerState.GetSteer();
@@ -203,7 +206,7 @@ void FCarlaEncoder::Visit(const UVehicleAgentComponent &Agent)
auto &Vehicle = Agent.GetVehicle();
::Encode(Vehicle.GetVehicleTransform(), Data.transform);
Data.type = CARLA_SERVER_AGENT_VEHICLE;
- Data.forward_speed = Vehicle.GetVehicleForwardSpeed();
+ Data.forward_speed = Vehicle.GetVehicleForwardSpeed() * TO_METERS;
::Encode(Vehicle.GetVehicleBoundsExtent(), Data.box_extent);
}
@@ -211,6 +214,6 @@ void FCarlaEncoder::Visit(const UWalkerAgentComponent &Agent)
{
::Encode(Agent.GetComponentTransform(), Data.transform);
Data.type = CARLA_SERVER_AGENT_PEDESTRIAN;
- Data.forward_speed = Agent.GetForwardSpeed();
+ Data.forward_speed = Agent.GetForwardSpeed() * TO_METERS;
::Encode(Agent.GetBoundingBoxExtent(), Data.box_extent);
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp
index 64106c035..695269950 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp
@@ -149,7 +149,7 @@ void UCarlaSettingsDelegate::LaunchLowQualityCommands(UWorld * world) const
GEngine->Exec(world,TEXT("r.SSR.MaxRoughness 0.1"));
GEngine->Exec(world,TEXT("r.AllowOcclusionQueries 1"));
//GEngine->Exec(world,TEXT("r.SSR 0"));
- GEngine->Exec(world,TEXT("r.StencilForLODDither 1"));
+ //GEngine->Exec(world,TEXT("r.StencilForLODDither 1")); //readonly
GEngine->Exec(world,TEXT("r.EarlyZPass 2")); //transparent before opaque
GEngine->Exec(world,TEXT("r.EarlyZPassMovable 1"));
GEngine->Exec(world,TEXT("Foliage.DitheredLOD 0"));
@@ -185,7 +185,7 @@ void UCarlaSettingsDelegate::SetAllRoads(UWorld* world, const float max_draw_dis
if(staticmeshcomponent)
{
staticmeshcomponent->bAllowCullDistanceVolume = (max_draw_distance>0);
- //staticmeshcomponent->bUseAsOccluder = false;
+ staticmeshcomponent->bUseAsOccluder = false;
staticmeshcomponent->LDMaxDrawDistance = max_draw_distance;
staticmeshcomponent->CastShadow = (max_draw_distance==0);
if(road_pieces_materials.Num()>0)
@@ -288,7 +288,7 @@ void UCarlaSettingsDelegate::LaunchEpicQualityCommands(UWorld* world) const
GEngine->Exec(world,TEXT("r.SceneColorFringeQuality 1"));
GEngine->Exec(world,TEXT("r.FastBlurThreshold 100"));
GEngine->Exec(world,TEXT("r.SSR.MaxRoughness -1"));
- GEngine->Exec(world,TEXT("r.StencilForLODDither 0"));
+ //GEngine->Exec(world,TEXT("r.StencilForLODDither 0")); //readonly
GEngine->Exec(world,TEXT("r.EarlyZPass 3"));
GEngine->Exec(world,TEXT("r.EarlyZPassMovable 1"));
GEngine->Exec(world,TEXT("Foliage.DitheredLOD 1"));
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp
index dd469ab74..356f2af28 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.cpp
@@ -9,7 +9,7 @@ void ULidarDescription::Load(const FIniFile &Config, const FString &Section)
{
Super::Load(Config, Section);
Config.GetInt(*Section, TEXT("Channels"), Channels);
- Config.GetFloat(*Section, TEXT("Range"), Range);
+ Config.GetFloat(*Section, TEXT("Range"), Range, 1e2);
Config.GetInt(*Section, TEXT("PointsPerSecond"), PointsPerSecond);
Config.GetFloat(*Section, TEXT("RotationFrequency"), RotationFrequency);
Config.GetFloat(*Section, TEXT("UpperFovLimit"), UpperFovLimit);
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h
index fd84511c9..1e7d3b2fb 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/LidarDescription.h
@@ -28,7 +28,7 @@ public:
UPROPERTY(EditDefaultsOnly, Category = "Lidar Description")
uint32 Channels = 32u;
- /** Measure distance. */
+ /** Measure distance in centimeters. */
UPROPERTY(EditDefaultsOnly, Category = "Lidar Description")
float Range = 5000.0f;
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp
index 446eca375..fb42a9ff1 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/SensorDescription.cpp
@@ -16,9 +16,10 @@ void USensorDescription::AcceptVisitor(ISensorDescriptionVisitor &Visitor) const
void USensorDescription::Load(const FIniFile &Config, const FString &Section)
{
- Config.GetFloat(*Section, TEXT("PositionX"), Position.X);
- Config.GetFloat(*Section, TEXT("PositionY"), Position.Y);
- Config.GetFloat(*Section, TEXT("PositionZ"), Position.Z);
+ constexpr float TO_CENTIMETERS = 1e2;
+ Config.GetFloat(*Section, TEXT("PositionX"), Position.X, TO_CENTIMETERS);
+ Config.GetFloat(*Section, TEXT("PositionY"), Position.Y, TO_CENTIMETERS);
+ Config.GetFloat(*Section, TEXT("PositionZ"), Position.Z, TO_CENTIMETERS);
Config.GetFloat(*Section, TEXT("RotationPitch"), Rotation.Pitch);
Config.GetFloat(*Section, TEXT("RotationYaw"), Rotation.Yaw);
Config.GetFloat(*Section, TEXT("RotationRoll"), Rotation.Roll);
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h
index 201416fba..f691bb2d5 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Util/IniFile.h
@@ -112,11 +112,11 @@ public:
}
}
- void GetFloat(const TCHAR* Section, const TCHAR* Key, float &Target) const
+ void GetFloat(const TCHAR* Section, const TCHAR* Key, float &Target, const float Factor = 1.0f) const
{
FString Value;
if (ConfigFile.GetString(Section, Key, Value)) {
- Target = FCString::Atof(*Value);
+ Target = Factor * FCString::Atof(*Value);
}
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp
index 4dc86c83b..62d5c6fb9 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp
@@ -94,7 +94,7 @@ void ACarlaVehicleController::OnCollisionEvent(
{
// Register collision only if we are moving faster than 1 km/h.
check(IsPossessingAVehicle());
- if (FMath::Abs(GetPossessedVehicle()->GetVehicleForwardSpeed()) > 1.0f) {
+ if (FMath::Abs(GetPossessedVehicle()->GetVehicleForwardSpeed() * 0.036f) > 1.0f) {
CarlaPlayerState->RegisterCollision(Actor, OtherActor, NormalImpulse, Hit);
}
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp
index d38d2f290..44ba18aaa 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp
@@ -46,7 +46,7 @@ FTransform ACarlaWheeledVehicle::GetVehicleTransform() const
float ACarlaWheeledVehicle::GetVehicleForwardSpeed() const
{
- return GetVehicleMovementComponent()->GetForwardSpeed() * 0.036f;
+ return GetVehicleMovementComponent()->GetForwardSpeed();
}
FVector ACarlaWheeledVehicle::GetVehicleOrientation() const
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h
index 0131c8f12..bba09afba 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h
@@ -46,7 +46,7 @@ public:
UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
FTransform GetVehicleTransform() const;
- /// Forward speed in km/h. Might be negative if goes backwards.
+ /// Forward speed in cm/s. Might be negative if goes backwards.
UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
float GetVehicleForwardSpeed() const;
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp
index 752c1f9cb..295b16960 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp
@@ -177,7 +177,8 @@ void AWheeledVehicleAIController::TickAutopilotController()
Steering = CalcStreeringValue(Direction);
}
- const auto Speed = Vehicle->GetVehicleForwardSpeed();
+ // Speed in km/h.
+ const auto Speed = Vehicle->GetVehicleForwardSpeed() * 0.036f;
float Throttle;
if (TrafficLightState != ETrafficLightState::Green) {
diff --git a/Util/CarlaServer/include/carla/carla_server.h b/Util/CarlaServer/include/carla/carla_server.h
index 74e14bbe0..59b014456 100644
--- a/Util/CarlaServer/include/carla/carla_server.h
+++ b/Util/CarlaServer/include/carla/carla_server.h
@@ -35,8 +35,11 @@ extern "C" {
};
struct carla_transform {
+ /** Location in meters. */
struct carla_vector3d location;
+ /** Unit vector pointing "forward". */
struct carla_vector3d orientation;
+ /** Rotation angles in degrees. */
struct carla_rotation3d rotation;
};
@@ -160,7 +163,7 @@ extern "C" {
struct carla_vector3d box_extent;
/** Current acceleration of the player. */
struct carla_vector3d acceleration;
- /** Forward speed in km/h. */
+ /** Forward speed in m/s. */
float forward_speed;
/** Collision intensity with other vehicles. */
float collision_vehicles;