diff --git a/.gitignore b/.gitignore
index b1cb5f56e..eeb82282e 100644
--- a/.gitignore
+++ b/.gitignore
@@ -27,4 +27,5 @@ __pycache__
_benchmarks_results
_images*
_out
+_site
core
diff --git a/.travis.yml b/.travis.yml
index 5f123a019..acff37a08 100644
--- a/.travis.yml
+++ b/.travis.yml
@@ -25,3 +25,18 @@ matrix:
- cppcheck
script:
- cppcheck . -iBuild -i.pb.cc --error-exitcode=1 --enable=warning --quiet
+
+ - env: TEST="MkDocs"
+ install:
+ - pip install mkdocs
+ script:
+ - mkdocs build --verbose --clean --strict --site-dir _site
+
+ - env: TEST="AwesomeBot"
+ install:
+ - gem install awesome_bot
+ script:
+ - find . -name '*.md' | xargs awesome_bot --allow-dupe --allow-redirect --skip-save-results
+
+notifications:
+ email: false
diff --git a/CARLA.sublime-project b/CARLA.sublime-project
index 74778e0f3..2eab9615d 100644
--- a/CARLA.sublime-project
+++ b/CARLA.sublime-project
@@ -18,7 +18,8 @@
"Intermediate",
"Saved",
"Unreal/CarlaUE4/Content*",
- "__pycache__"
+ "__pycache__",
+ "_site"
],
"file_exclude_patterns":
[
diff --git a/Docs/CONTRIBUTING.md b/Docs/CONTRIBUTING.md
index 677603064..cd966e32f 100644
--- a/Docs/CONTRIBUTING.md
+++ b/Docs/CONTRIBUTING.md
@@ -101,7 +101,7 @@ spawned. Note that the blueprint can call back C++ functions, for instance for
getting the random engine. This way there is a back-and-forth communication
between C++ code and blueprints.
-[capturelink]: https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/SceneCaptureToDiskCamera.h
+[capturelink]: https://github.com/carla-simulator/carla/blob/master/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureToDiskCamera.h
#### Coding standard
diff --git a/Docs/cameras_and_sensors.md b/Docs/cameras_and_sensors.md
index 310597f6a..c2afd113f 100644
--- a/Docs/cameras_and_sensors.md
+++ b/Docs/cameras_and_sensors.md
@@ -35,6 +35,11 @@ to a more human readable palette of colors. It can be found at
["Util/ImageConverter"][imgconvlink]. Alternatively, they can also be converted
using the functions at `carla.image_converter` Python module.
+Note that all the sensor data comes with a _frame number_ stamp, this _frame
+number_ matches the one received in the measurements. This is especially useful
+for running the simulator in asynchronous mode and synchronize sensor data on
+the client side.
+
[clientexamplelink]: https://github.com/carla-simulator/carla/blob/master/PythonClient/client_example.py
[settingslink]: https://github.com/carla-simulator/carla/blob/master/Docs/Example.CarlaSettings.ini
[imgconvlink]: https://github.com/carla-simulator/carla/tree/master/Util/ImageConverter
diff --git a/Docs/measurements.md b/Docs/measurements.md
index 88d6b86cd..55c787ff6 100644
--- a/Docs/measurements.md
+++ b/Docs/measurements.md
@@ -11,13 +11,13 @@ to the client. This document describes the details of these measurements.
Time-stamps
-----------
-Since CARLA can be run at fixed-frame rate, we keep track of two different
-time-stamps.
+Every frame is described by three different counters/time-stamps
Key | Type | Units | Description
-------------------------- | --------- | ------------ | ------------
+frame_number | uint64 | | Frame counter (it is **not** restarted on each episode).
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.
+game_timestamp | uint32 | milliseconds | In-game time-stamp, elapsed since the beginning of the current episode.
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
@@ -126,18 +126,68 @@ If enabled, the server attaches a list of agents to the measurements package
every frame. Each of these agents has an unique id that identifies it, and
belongs to one of the following classes
- * **Vehicle** Contains its transform, box-extent, and forward speed.
- * **Pedestrian** Contains its transform, box-extent, and forward speed. (*)
- * **Traffic light** Contains its transform and state (green, yellow, red).
- * **Speed-limit sign** Contains its transform and speed-limit.
+ * Vehicle
+ * Pedestrian
+ * Traffic ligth
+ * Speed limit sign
-(*) At this point every pedestrian is assumed to have the same bounding-box
-size.
+Each of them can be accessed in Python by checking if the agent object has the
+field enabled
+
+```python
+measurements, sensor_data = client.read_data()
+
+for agent in measurements.non_player_agents:
+ agent.id # unique id of the agent
+ if agent.HasField('vehicle'):
+ agent.vehicle.forward_speed
+ agent.vehicle.transform
+ agent.vehicle.bounding_box
+```
+
+
Vehicle
+
+Key | Type | Description
+------------------------------- | --------- | ------------
+id | uint32 | Agent ID
+vehicle.forward_speed | float | Forward speed of the vehicle in m/s
+vehicle.transform | Transform | Agent-to-world transform
+vehicle.bounding_box.transform | Transform | Transform of the bounding box relative to the vehicle
+vehicle.bounding_box.extent | Vector3D | Radii dimensions of the bounding box in meters
+
+Pedestrian
+
+Key | Type | Description
+--------------------------------- | --------- | ------------
+id | uint32 | Agent ID
+pedestrian.forward_speed | float | Forward speed of the pedestrian in m/s
+pedestrian.transform | Transform | Agent-to-world transform
+pedestrian.bounding_box.transform | Transform | Transform of the bounding box relative to the pedestrian
+pedestrian.bounding_box.extent | Vector3D | Radii dimensions of the bounding box in meters (*)
+
+(*) At this point every pedestrian is assumed to have the same
+bounding-box size.
+
+Traffic light
+
+Key | Type | Description
+---------------------------- | --------- | ------------
+id | uint32 | Agent ID
+traffic_light.transform | Transform | Agent-to-world transform
+traffic_light.state | enum | Traffic light state; `GREEN`, `YELLOW`, or `RED`
+
+Speed limit sign
+
+Key | Type | Description
+---------------------------- | --------- | ------------
+id | uint32 | Agent ID
+speed_limit_sign.transform | Transform | Agent-to-world transform
+speed_limit_sign.speed_limit | float | Speed limit in m/s
Transform and bounding box
-The transform defines the location and orientation of the agent. The bounding
-box is centered at the agent's location. The box extent gives the radii
-dimensions of the bounding box of the agent.
+The transform defines the location and orientation of the agent. The transform
+of the bounding box is given relative to the vehicle. The box extent gives the
+radii dimensions of the bounding box of the agent.
![Vehicle Bounding Box](img/vehicle_bounding_box.png)
diff --git a/Makefile b/Makefile
index 39d64e3d2..031dcdefa 100644
--- a/Makefile
+++ b/Makefile
@@ -35,6 +35,11 @@ vsproject: MY_CMAKE_FLAGS+=-DCMAKE_BUILD_TYPE=Release
vsproject: MY_CMAKE_FLAGS+=-G "Visual Studio 14 2015 Win64"
vsproject: call_cmake
+vsproject15: BUILD_FOLDER=$(BASE_BUILD_FOLDER)/visualstudio
+vsproject15: MY_CMAKE_FLAGS+=-DCMAKE_BUILD_TYPE=Release
+vsproject15: MY_CMAKE_FLAGS+=-G "Visual Studio 15 2017 Win64"
+vsproject15: call_cmake
+
build_linux: MY_CMAKE_FLAGS+=-G "Ninja"
build_linux: call_cmake
@cd $(BUILD_FOLDER) && ninja && ninja install
diff --git a/PythonClient/carla/carla_server_pb2.py b/PythonClient/carla/carla_server_pb2.py
index 913579280..19a43e1c9 100644
--- a/PythonClient/carla/carla_server_pb2.py
+++ b/PythonClient/carla/carla_server_pb2.py
@@ -19,7 +19,7 @@ DESCRIPTOR = _descriptor.FileDescriptor(
name='carla_server.proto',
package='carla_server',
syntax='proto3',
- serialized_pb=_b('\n\x12\x63\x61rla_server.proto\x12\x0c\x63\x61rla_server\"+\n\x08Vector3D\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\"6\n\nRotation3D\x12\r\n\x05pitch\x18\x01 \x01(\x02\x12\x0b\n\x03yaw\x18\x02 \x01(\x02\x12\x0c\n\x04roll\x18\x03 \x01(\x02\"\x92\x01\n\tTransform\x12(\n\x08location\x18\x01 \x01(\x0b\x32\x16.carla_server.Vector3D\x12/\n\x0borientation\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3DB\x02\x18\x01\x12*\n\x08rotation\x18\x03 \x01(\x0b\x32\x18.carla_server.Rotation3D\"\x80\x01\n\x06Sensor\x12\n\n\x02id\x18\x01 \x01(\x07\x12\'\n\x04type\x18\x02 \x01(\x0e\x32\x19.carla_server.Sensor.Type\x12\x0c\n\x04name\x18\x03 \x01(\t\"3\n\x04Type\x12\x0b\n\x07UNKNOWN\x10\x00\x12\n\n\x06\x43\x41MERA\x10\x01\x12\x12\n\x0eLIDAR_RAY_CAST\x10\x02\"x\n\x07Vehicle\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"{\n\nPedestrian\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"\x94\x01\n\x0cTrafficLight\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x05state\x18\x02 \x01(\x0e\x32 .carla_server.TrafficLight.State\"\'\n\x05State\x12\t\n\x05GREEN\x10\x00\x12\n\n\x06YELLOW\x10\x01\x12\x07\n\x03RED\x10\x02\"Q\n\x0eSpeedLimitSign\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12\x13\n\x0bspeed_limit\x18\x02 \x01(\x02\"\xe5\x01\n\x05\x41gent\x12\n\n\x02id\x18\x01 \x01(\x07\x12(\n\x07vehicle\x18\x02 \x01(\x0b\x32\x15.carla_server.VehicleH\x00\x12.\n\npedestrian\x18\x03 \x01(\x0b\x32\x18.carla_server.PedestrianH\x00\x12\x33\n\rtraffic_light\x18\x04 \x01(\x0b\x32\x1a.carla_server.TrafficLightH\x00\x12\x38\n\x10speed_limit_sign\x18\x05 \x01(\x0b\x32\x1c.carla_server.SpeedLimitSignH\x00\x42\x07\n\x05\x61gent\"%\n\x11RequestNewEpisode\x12\x10\n\x08ini_file\x18\x01 \x01(\t\"n\n\x10SceneDescription\x12\x33\n\x12player_start_spots\x18\x01 \x03(\x0b\x32\x17.carla_server.Transform\x12%\n\x07sensors\x18\x02 \x03(\x0b\x32\x14.carla_server.Sensor\"/\n\x0c\x45pisodeStart\x12\x1f\n\x17player_start_spot_index\x18\x01 \x01(\r\"\x1d\n\x0c\x45pisodeReady\x12\r\n\x05ready\x18\x01 \x01(\x08\"^\n\x07\x43ontrol\x12\r\n\x05steer\x18\x01 \x01(\x02\x12\x10\n\x08throttle\x18\x02 \x01(\x02\x12\r\n\x05\x62rake\x18\x03 \x01(\x02\x12\x12\n\nhand_brake\x18\x04 \x01(\x08\x12\x0f\n\x07reverse\x18\x05 \x01(\x08\"\xb6\x04\n\x0cMeasurements\x12\x1a\n\x12platform_timestamp\x18\x01 \x01(\r\x12\x16\n\x0egame_timestamp\x18\x02 \x01(\r\x12J\n\x13player_measurements\x18\x03 \x01(\x0b\x32-.carla_server.Measurements.PlayerMeasurements\x12.\n\x11non_player_agents\x18\x04 \x03(\x0b\x32\x13.carla_server.Agent\x1a\xf5\x02\n\x12PlayerMeasurements\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12*\n\nbox_extent\x18\x0b \x01(\x0b\x32\x16.carla_server.Vector3D\x12,\n\x0c\x61\x63\x63\x65leration\x18\x03 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x04 \x01(\x02\x12\x1a\n\x12\x63ollision_vehicles\x18\x05 \x01(\x02\x12\x1d\n\x15\x63ollision_pedestrians\x18\x06 \x01(\x02\x12\x17\n\x0f\x63ollision_other\x18\x07 \x01(\x02\x12\x1e\n\x16intersection_otherlane\x18\x08 \x01(\x02\x12\x1c\n\x14intersection_offroad\x18\t \x01(\x02\x12\x30\n\x11\x61utopilot_control\x18\n \x01(\x0b\x32\x15.carla_server.ControlB\x03\xf8\x01\x01\x62\x06proto3')
+ serialized_pb=_b('\n\x12\x63\x61rla_server.proto\x12\x0c\x63\x61rla_server\"+\n\x08Vector3D\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\"6\n\nRotation3D\x12\r\n\x05pitch\x18\x01 \x01(\x02\x12\x0b\n\x03yaw\x18\x02 \x01(\x02\x12\x0c\n\x04roll\x18\x03 \x01(\x02\"\x92\x01\n\tTransform\x12(\n\x08location\x18\x01 \x01(\x0b\x32\x16.carla_server.Vector3D\x12/\n\x0borientation\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3DB\x02\x18\x01\x12*\n\x08rotation\x18\x03 \x01(\x0b\x32\x18.carla_server.Rotation3D\"a\n\x0b\x42oundingBox\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12&\n\x06\x65xtent\x18\x02 \x01(\x0b\x32\x16.carla_server.Vector3D\"\x80\x01\n\x06Sensor\x12\n\n\x02id\x18\x01 \x01(\x07\x12\'\n\x04type\x18\x02 \x01(\x0e\x32\x19.carla_server.Sensor.Type\x12\x0c\n\x04name\x18\x03 \x01(\t\"3\n\x04Type\x12\x0b\n\x07UNKNOWN\x10\x00\x12\n\n\x06\x43\x41MERA\x10\x01\x12\x12\n\x0eLIDAR_RAY_CAST\x10\x02\"}\n\x07Vehicle\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x0c\x62ounding_box\x18\x04 \x01(\x0b\x32\x19.carla_server.BoundingBox\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"\x80\x01\n\nPedestrian\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x0c\x62ounding_box\x18\x04 \x01(\x0b\x32\x19.carla_server.BoundingBox\x12\x15\n\rforward_speed\x18\x03 \x01(\x02\"\x94\x01\n\x0cTrafficLight\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x05state\x18\x02 \x01(\x0e\x32 .carla_server.TrafficLight.State\"\'\n\x05State\x12\t\n\x05GREEN\x10\x00\x12\n\n\x06YELLOW\x10\x01\x12\x07\n\x03RED\x10\x02\"Q\n\x0eSpeedLimitSign\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12\x13\n\x0bspeed_limit\x18\x02 \x01(\x02\"\xe5\x01\n\x05\x41gent\x12\n\n\x02id\x18\x01 \x01(\x07\x12(\n\x07vehicle\x18\x02 \x01(\x0b\x32\x15.carla_server.VehicleH\x00\x12.\n\npedestrian\x18\x03 \x01(\x0b\x32\x18.carla_server.PedestrianH\x00\x12\x33\n\rtraffic_light\x18\x04 \x01(\x0b\x32\x1a.carla_server.TrafficLightH\x00\x12\x38\n\x10speed_limit_sign\x18\x05 \x01(\x0b\x32\x1c.carla_server.SpeedLimitSignH\x00\x42\x07\n\x05\x61gent\"%\n\x11RequestNewEpisode\x12\x10\n\x08ini_file\x18\x01 \x01(\t\"n\n\x10SceneDescription\x12\x33\n\x12player_start_spots\x18\x01 \x03(\x0b\x32\x17.carla_server.Transform\x12%\n\x07sensors\x18\x02 \x03(\x0b\x32\x14.carla_server.Sensor\"/\n\x0c\x45pisodeStart\x12\x1f\n\x17player_start_spot_index\x18\x01 \x01(\r\"\x1d\n\x0c\x45pisodeReady\x12\r\n\x05ready\x18\x01 \x01(\x08\"^\n\x07\x43ontrol\x12\r\n\x05steer\x18\x01 \x01(\x02\x12\x10\n\x08throttle\x18\x02 \x01(\x02\x12\r\n\x05\x62rake\x18\x03 \x01(\x02\x12\x12\n\nhand_brake\x18\x04 \x01(\x08\x12\x0f\n\x07reverse\x18\x05 \x01(\x08\"\xd1\x04\n\x0cMeasurements\x12\x14\n\x0c\x66rame_number\x18\x05 \x01(\x04\x12\x1a\n\x12platform_timestamp\x18\x01 \x01(\r\x12\x16\n\x0egame_timestamp\x18\x02 \x01(\r\x12J\n\x13player_measurements\x18\x03 \x01(\x0b\x32-.carla_server.Measurements.PlayerMeasurements\x12.\n\x11non_player_agents\x18\x04 \x03(\x0b\x32\x13.carla_server.Agent\x1a\xfa\x02\n\x12PlayerMeasurements\x12*\n\ttransform\x18\x01 \x01(\x0b\x32\x17.carla_server.Transform\x12/\n\x0c\x62ounding_box\x18\x0c \x01(\x0b\x32\x19.carla_server.BoundingBox\x12,\n\x0c\x61\x63\x63\x65leration\x18\x03 \x01(\x0b\x32\x16.carla_server.Vector3D\x12\x15\n\rforward_speed\x18\x04 \x01(\x02\x12\x1a\n\x12\x63ollision_vehicles\x18\x05 \x01(\x02\x12\x1d\n\x15\x63ollision_pedestrians\x18\x06 \x01(\x02\x12\x17\n\x0f\x63ollision_other\x18\x07 \x01(\x02\x12\x1e\n\x16intersection_otherlane\x18\x08 \x01(\x02\x12\x1c\n\x14intersection_offroad\x18\t \x01(\x02\x12\x30\n\x11\x61utopilot_control\x18\n \x01(\x0b\x32\x15.carla_server.ControlB\x03\xf8\x01\x01\x62\x06proto3')
)
@@ -45,8 +45,8 @@ _SENSOR_TYPE = _descriptor.EnumDescriptor(
],
containing_type=None,
options=None,
- serialized_start=364,
- serialized_end=415,
+ serialized_start=463,
+ serialized_end=514,
)
_sym_db.RegisterEnumDescriptor(_SENSOR_TYPE)
@@ -71,8 +71,8 @@ _TRAFFICLIGHT_STATE = _descriptor.EnumDescriptor(
],
containing_type=None,
options=None,
- serialized_start=774,
- serialized_end=813,
+ serialized_start=884,
+ serialized_end=923,
)
_sym_db.RegisterEnumDescriptor(_TRAFFICLIGHT_STATE)
@@ -212,6 +212,44 @@ _TRANSFORM = _descriptor.Descriptor(
)
+_BOUNDINGBOX = _descriptor.Descriptor(
+ name='BoundingBox',
+ full_name='carla_server.BoundingBox',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(
+ name='transform', full_name='carla_server.BoundingBox.transform', index=0,
+ number=1, type=11, cpp_type=10, label=1,
+ has_default_value=False, default_value=None,
+ message_type=None, enum_type=None, containing_type=None,
+ is_extension=False, extension_scope=None,
+ options=None),
+ _descriptor.FieldDescriptor(
+ name='extent', full_name='carla_server.BoundingBox.extent', index=1,
+ number=2, type=11, cpp_type=10, label=1,
+ has_default_value=False, default_value=None,
+ message_type=None, enum_type=None, containing_type=None,
+ is_extension=False, extension_scope=None,
+ options=None),
+ ],
+ extensions=[
+ ],
+ nested_types=[],
+ enum_types=[
+ ],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[
+ ],
+ serialized_start=286,
+ serialized_end=383,
+)
+
+
_SENSOR = _descriptor.Descriptor(
name='Sensor',
full_name='carla_server.Sensor',
@@ -253,8 +291,8 @@ _SENSOR = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=287,
- serialized_end=415,
+ serialized_start=386,
+ serialized_end=514,
)
@@ -273,8 +311,8 @@ _VEHICLE = _descriptor.Descriptor(
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
- name='box_extent', full_name='carla_server.Vehicle.box_extent', index=1,
- number=2, type=11, cpp_type=10, label=1,
+ name='bounding_box', full_name='carla_server.Vehicle.bounding_box', index=1,
+ number=4, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
@@ -298,8 +336,8 @@ _VEHICLE = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=417,
- serialized_end=537,
+ serialized_start=516,
+ serialized_end=641,
)
@@ -318,8 +356,8 @@ _PEDESTRIAN = _descriptor.Descriptor(
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
- name='box_extent', full_name='carla_server.Pedestrian.box_extent', index=1,
- number=2, type=11, cpp_type=10, label=1,
+ name='bounding_box', full_name='carla_server.Pedestrian.bounding_box', index=1,
+ number=4, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
@@ -343,8 +381,8 @@ _PEDESTRIAN = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=539,
- serialized_end=662,
+ serialized_start=644,
+ serialized_end=772,
)
@@ -382,8 +420,8 @@ _TRAFFICLIGHT = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=665,
- serialized_end=813,
+ serialized_start=775,
+ serialized_end=923,
)
@@ -420,8 +458,8 @@ _SPEEDLIMITSIGN = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=815,
- serialized_end=896,
+ serialized_start=925,
+ serialized_end=1006,
)
@@ -482,8 +520,8 @@ _AGENT = _descriptor.Descriptor(
name='agent', full_name='carla_server.Agent.agent',
index=0, containing_type=None, fields=[]),
],
- serialized_start=899,
- serialized_end=1128,
+ serialized_start=1009,
+ serialized_end=1238,
)
@@ -513,8 +551,8 @@ _REQUESTNEWEPISODE = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=1130,
- serialized_end=1167,
+ serialized_start=1240,
+ serialized_end=1277,
)
@@ -551,8 +589,8 @@ _SCENEDESCRIPTION = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=1169,
- serialized_end=1279,
+ serialized_start=1279,
+ serialized_end=1389,
)
@@ -582,8 +620,8 @@ _EPISODESTART = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=1281,
- serialized_end=1328,
+ serialized_start=1391,
+ serialized_end=1438,
)
@@ -613,8 +651,8 @@ _EPISODEREADY = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=1330,
- serialized_end=1359,
+ serialized_start=1440,
+ serialized_end=1469,
)
@@ -672,8 +710,8 @@ _CONTROL = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=1361,
- serialized_end=1455,
+ serialized_start=1471,
+ serialized_end=1565,
)
@@ -692,8 +730,8 @@ _MEASUREMENTS_PLAYERMEASUREMENTS = _descriptor.Descriptor(
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
- name='box_extent', full_name='carla_server.Measurements.PlayerMeasurements.box_extent', index=1,
- number=11, type=11, cpp_type=10, label=1,
+ name='bounding_box', full_name='carla_server.Measurements.PlayerMeasurements.bounding_box', index=1,
+ number=12, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
@@ -766,8 +804,8 @@ _MEASUREMENTS_PLAYERMEASUREMENTS = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=1651,
- serialized_end=2024,
+ serialized_start=1783,
+ serialized_end=2161,
)
_MEASUREMENTS = _descriptor.Descriptor(
@@ -778,28 +816,35 @@ _MEASUREMENTS = _descriptor.Descriptor(
containing_type=None,
fields=[
_descriptor.FieldDescriptor(
- name='platform_timestamp', full_name='carla_server.Measurements.platform_timestamp', index=0,
+ name='frame_number', full_name='carla_server.Measurements.frame_number', index=0,
+ number=5, type=4, cpp_type=4, label=1,
+ has_default_value=False, default_value=0,
+ message_type=None, enum_type=None, containing_type=None,
+ is_extension=False, extension_scope=None,
+ options=None),
+ _descriptor.FieldDescriptor(
+ name='platform_timestamp', full_name='carla_server.Measurements.platform_timestamp', index=1,
number=1, type=13, cpp_type=3, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
- name='game_timestamp', full_name='carla_server.Measurements.game_timestamp', index=1,
+ name='game_timestamp', full_name='carla_server.Measurements.game_timestamp', index=2,
number=2, type=13, cpp_type=3, label=1,
has_default_value=False, default_value=0,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
- name='player_measurements', full_name='carla_server.Measurements.player_measurements', index=2,
+ name='player_measurements', full_name='carla_server.Measurements.player_measurements', index=3,
number=3, type=11, cpp_type=10, label=1,
has_default_value=False, default_value=None,
message_type=None, enum_type=None, containing_type=None,
is_extension=False, extension_scope=None,
options=None),
_descriptor.FieldDescriptor(
- name='non_player_agents', full_name='carla_server.Measurements.non_player_agents', index=3,
+ name='non_player_agents', full_name='carla_server.Measurements.non_player_agents', index=4,
number=4, type=11, cpp_type=10, label=3,
has_default_value=False, default_value=[],
message_type=None, enum_type=None, containing_type=None,
@@ -817,19 +862,21 @@ _MEASUREMENTS = _descriptor.Descriptor(
extension_ranges=[],
oneofs=[
],
- serialized_start=1458,
- serialized_end=2024,
+ serialized_start=1568,
+ serialized_end=2161,
)
_TRANSFORM.fields_by_name['location'].message_type = _VECTOR3D
_TRANSFORM.fields_by_name['orientation'].message_type = _VECTOR3D
_TRANSFORM.fields_by_name['rotation'].message_type = _ROTATION3D
+_BOUNDINGBOX.fields_by_name['transform'].message_type = _TRANSFORM
+_BOUNDINGBOX.fields_by_name['extent'].message_type = _VECTOR3D
_SENSOR.fields_by_name['type'].enum_type = _SENSOR_TYPE
_SENSOR_TYPE.containing_type = _SENSOR
_VEHICLE.fields_by_name['transform'].message_type = _TRANSFORM
-_VEHICLE.fields_by_name['box_extent'].message_type = _VECTOR3D
+_VEHICLE.fields_by_name['bounding_box'].message_type = _BOUNDINGBOX
_PEDESTRIAN.fields_by_name['transform'].message_type = _TRANSFORM
-_PEDESTRIAN.fields_by_name['box_extent'].message_type = _VECTOR3D
+_PEDESTRIAN.fields_by_name['bounding_box'].message_type = _BOUNDINGBOX
_TRAFFICLIGHT.fields_by_name['transform'].message_type = _TRANSFORM
_TRAFFICLIGHT.fields_by_name['state'].enum_type = _TRAFFICLIGHT_STATE
_TRAFFICLIGHT_STATE.containing_type = _TRAFFICLIGHT
@@ -853,7 +900,7 @@ _AGENT.fields_by_name['speed_limit_sign'].containing_oneof = _AGENT.oneofs_by_na
_SCENEDESCRIPTION.fields_by_name['player_start_spots'].message_type = _TRANSFORM
_SCENEDESCRIPTION.fields_by_name['sensors'].message_type = _SENSOR
_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['transform'].message_type = _TRANSFORM
-_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['box_extent'].message_type = _VECTOR3D
+_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['bounding_box'].message_type = _BOUNDINGBOX
_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['acceleration'].message_type = _VECTOR3D
_MEASUREMENTS_PLAYERMEASUREMENTS.fields_by_name['autopilot_control'].message_type = _CONTROL
_MEASUREMENTS_PLAYERMEASUREMENTS.containing_type = _MEASUREMENTS
@@ -862,6 +909,7 @@ _MEASUREMENTS.fields_by_name['non_player_agents'].message_type = _AGENT
DESCRIPTOR.message_types_by_name['Vector3D'] = _VECTOR3D
DESCRIPTOR.message_types_by_name['Rotation3D'] = _ROTATION3D
DESCRIPTOR.message_types_by_name['Transform'] = _TRANSFORM
+DESCRIPTOR.message_types_by_name['BoundingBox'] = _BOUNDINGBOX
DESCRIPTOR.message_types_by_name['Sensor'] = _SENSOR
DESCRIPTOR.message_types_by_name['Vehicle'] = _VEHICLE
DESCRIPTOR.message_types_by_name['Pedestrian'] = _PEDESTRIAN
@@ -897,6 +945,13 @@ Transform = _reflection.GeneratedProtocolMessageType('Transform', (_message.Mess
))
_sym_db.RegisterMessage(Transform)
+BoundingBox = _reflection.GeneratedProtocolMessageType('BoundingBox', (_message.Message,), dict(
+ DESCRIPTOR = _BOUNDINGBOX,
+ __module__ = 'carla_server_pb2'
+ # @@protoc_insertion_point(class_scope:carla_server.BoundingBox)
+ ))
+_sym_db.RegisterMessage(BoundingBox)
+
Sensor = _reflection.GeneratedProtocolMessageType('Sensor', (_message.Message,), dict(
DESCRIPTOR = _SENSOR,
__module__ = 'carla_server_pb2'
diff --git a/PythonClient/carla/client.py b/PythonClient/carla/client.py
index c2550c020..d2700924e 100644
--- a/PythonClient/carla/client.py
+++ b/PythonClient/carla/client.py
@@ -183,31 +183,36 @@ class CarlaClient(object):
def _make_sensor_parsers(sensors):
image_types = ['None', 'SceneFinal', 'Depth', 'SemanticSegmentation']
getimgtype = lambda id: image_types[id] if len(image_types) > id else 'Unknown'
- getint = lambda data, index: struct.unpack('(World->GetAuthGameMode());
+ ACarlaGameModeBase *GameMode = Cast(World->GetAuthGameMode());
check(GameMode != nullptr);
return GameMode->GetDataRouter();
}
@@ -40,7 +42,20 @@ void UAgentComponent::BeginPlay()
if (bRegisterAgentComponent)
{
- GetDataRouter(GetWorld()).RegisterAgent(this);
+ /**
+ * This only returns true if the current game mode is not null
+ * because you can only access a game mode if you are the host
+ * @param oftheworld UWorld is needed to access the game mode
+ * @return true if there is a game mode and it is not null
+ */
+ if(UGameplayStatics::GetGameMode(GetWorld())!=nullptr)
+ {
+ GetDataRouter(GetWorld()).RegisterAgent(this);
+ } else
+ {
+ UCarlaGameInstance* GameInstance = Cast(UGameplayStatics::GetGameInstance(GetWorld()));
+ if(GameInstance) GameInstance->GetDataRouter().RegisterAgent(this);
+ }
bAgentComponentIsRegistered = true;
}
}
@@ -49,9 +64,19 @@ void UAgentComponent::EndPlay(const EEndPlayReason::Type EndPlayReason)
{
if (bAgentComponentIsRegistered)
{
- GetDataRouter(GetWorld()).DeregisterAgent(this);
+ if(UGameplayStatics::GetGameMode(GetWorld())!=nullptr)
+ {
+ GetDataRouter(GetWorld()).DeregisterAgent(this);
+ }
+ else
+ {
+ UCarlaGameInstance* GameInstance = Cast(UGameplayStatics::GetGameInstance(GetWorld()));
+ if(GameInstance)
+ GameInstance->GetDataRouter().DeregisterAgent(this);
+ }
bAgentComponentIsRegistered = false;
}
Super::EndPlay(EndPlayReason);
}
+
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.cpp
index b5be052b7..edce600ba 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.cpp
@@ -9,11 +9,9 @@
#include "Carla.h"
#include "VehicleAgentComponent.h"
-#include "Vehicle/CarlaWheeledVehicle.h"
-
-static bool IsPlayer(const ACarlaWheeledVehicle &Vehicle)
+static bool IsPlayer(const ACarlaWheeledVehicle &InVehicle)
{
- auto *Controller = Cast(Vehicle.GetController());
+ auto *Controller = Cast(InVehicle.GetController());
return (Controller != nullptr) && Controller->IsPossessingThePlayer();
}
@@ -22,11 +20,11 @@ UVehicleAgentComponent::UVehicleAgentComponent(const FObjectInitializer &ObjectI
void UVehicleAgentComponent::BeginPlay()
{
- WheeledVehicle = Cast(GetOwner());
- checkf(WheeledVehicle != nullptr, TEXT("UVehicleAgentComponent can only be attached to ACarlaWheeledVehicle"));
+ Vehicle = Cast(GetOwner());
+ checkf(Vehicle != nullptr, TEXT("UVehicleAgentComponent can only be attached to ACarlaWheeledVehicle"));
// We only want to register non-player agents.
- bRegisterAgentComponent = !IsPlayer(*WheeledVehicle);
+ bRegisterAgentComponent = !IsPlayer(*Vehicle);
Super::BeginPlay();
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.h
index b4904e054..0acc92a83 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/VehicleAgentComponent.h
@@ -8,9 +8,9 @@
#include "Agent/AgentComponent.h"
-#include "VehicleAgentComponent.generated.h"
+#include "Vehicle/CarlaWheeledVehicle.h"
-class ACarlaWheeledVehicle;
+#include "VehicleAgentComponent.generated.h"
UCLASS(ClassGroup=(Custom), meta=(BlueprintSpawnableComponent))
class CARLA_API UVehicleAgentComponent : public UAgentComponent
@@ -21,10 +21,25 @@ public:
UVehicleAgentComponent(const FObjectInitializer &ObjectInitializer);
- ACarlaWheeledVehicle &GetVehicle() const
+ /// Return forward speed in cm/s.
+ float GetForwardSpeed() const
{
- check(WheeledVehicle != nullptr);
- return *WheeledVehicle;
+ return Vehicle->GetVehicleForwardSpeed();
+ }
+
+ FTransform GetTransform() const
+ {
+ return Vehicle->GetVehicleTransform();
+ }
+
+ FTransform GetBoundingBoxTransform() const
+ {
+ return Vehicle->GetVehicleBoundingBoxTransform();
+ }
+
+ FVector GetBoundingBoxExtent() const
+ {
+ return Vehicle->GetVehicleBoundingBoxExtent();
}
protected:
@@ -38,5 +53,6 @@ protected:
private:
- ACarlaWheeledVehicle *WheeledVehicle = nullptr;
+ UPROPERTY()
+ ACarlaWheeledVehicle *Vehicle = nullptr;
};
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp
index 553816786..ad85de085 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.cpp
@@ -9,17 +9,9 @@
#include "Carla.h"
#include "WalkerAgentComponent.h"
-#include "GameFramework/Character.h"
-
UWalkerAgentComponent::UWalkerAgentComponent(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer) {}
-float UWalkerAgentComponent::GetForwardSpeed() const
-{
- /// @todo Is it necessary to compute this speed every tick?
- return FVector::DotProduct(Walker->GetVelocity(), Walker->GetActorRotation().Vector());
-}
-
void UWalkerAgentComponent::BeginPlay()
{
Walker = Cast(GetOwner());
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h
index 111b41d37..7bae45440 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Agent/WalkerAgentComponent.h
@@ -8,9 +8,9 @@
#include "Agent/AgentComponent.h"
-#include "WalkerAgentComponent.generated.h"
+#include "GameFramework/Character.h"
-class ACharacter;
+#include "WalkerAgentComponent.generated.h"
/// This component can be added to any ACharacter to be added as agent.
/// See UAgentComponent.
@@ -24,7 +24,20 @@ public:
UWalkerAgentComponent(const FObjectInitializer &ObjectInitializer);
/// Return forward speed in cm/s.
- float GetForwardSpeed() const;
+ float GetForwardSpeed() const
+ {
+ return FVector::DotProduct(Walker->GetVelocity(), Walker->GetActorRotation().Vector());
+ }
+
+ FTransform GetTransform() const
+ {
+ return Walker->GetActorTransform();
+ }
+
+ FTransform GetBoundingBoxTransform() const
+ {
+ return FTransform();
+ }
FVector GetBoundingBoxExtent() const
{
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp
index 24359b817..ff62ff4b2 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaGameModeBase.cpp
@@ -202,7 +202,7 @@ void ACarlaGameModeBase::BeginPlay()
void ACarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
{
Super::EndPlay(EndPlayReason);
- if (CarlaSettingsDelegate != nullptr)
+ if (CarlaSettingsDelegate != nullptr && EndPlayReason!=EEndPlayReason::EndPlayInEditor)
{
CarlaSettingsDelegate->Reset();
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.cpp
index 03eb98d08..03ea0b4d8 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.cpp
@@ -7,6 +7,8 @@
#include "Carla.h"
#include "CarlaPlayerState.h"
+#include "CoreGlobals.h"
+
void ACarlaPlayerState::Reset()
{
Super::Reset();
@@ -25,6 +27,7 @@ void ACarlaPlayerState::CopyProperties(APlayerState *PlayerState)
ACarlaPlayerState *Other = Cast(PlayerState);
if (Other != nullptr)
{
+ FrameNumber = Other->FrameNumber;
FramesPerSecond = Other->FramesPerSecond;
PlatformTimeStamp = Other->PlatformTimeStamp;
GameTimeStamp = Other->GameTimeStamp;
@@ -74,6 +77,7 @@ static int32 RoundToMilliseconds(float Seconds)
void ACarlaPlayerState::UpdateTimeStamp(float DeltaSeconds)
{
+ FrameNumber = GFrameCounter;
FramesPerSecond = 1.0f / DeltaSeconds;
PlatformTimeStamp = RoundToMilliseconds(FPlatformTime::Seconds());
GameTimeStamp += RoundToMilliseconds(DeltaSeconds);
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.h
index 97f8f0dc3..f1404d74f 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Game/CarlaPlayerState.h
@@ -40,6 +40,11 @@ public:
// ===========================================================================
/// @{
+ uint64 GetFrameNumber() const
+ {
+ return FrameNumber;
+ }
+
UFUNCTION(BlueprintCallable)
float GetFramesPerSecond() const
{
@@ -83,9 +88,15 @@ public:
}
UFUNCTION(BlueprintCallable)
- FVector GetBoundsExtent() const
+ FTransform GetBoundingBoxTransform() const
{
- return BoundsExtent;
+ return BoundingBoxTransform;
+ }
+
+ UFUNCTION(BlueprintCallable)
+ FVector GetBoundingBoxExtent() const
+ {
+ return BoundingBoxExtent;
}
UFUNCTION(BlueprintCallable)
@@ -214,6 +225,9 @@ private:
// If you add another variable here, don't forget to copy it inside
// CopyProperties if necessary.
+ UPROPERTY(VisibleAnywhere)
+ uint64 FrameNumber;
+
UPROPERTY(VisibleAnywhere)
float FramesPerSecond;
@@ -227,7 +241,10 @@ private:
FTransform Transform;
UPROPERTY(VisibleAnywhere)
- FVector BoundsExtent;
+ FTransform BoundingBoxTransform;
+
+ UPROPERTY(VisibleAnywhere)
+ FVector BoundingBoxExtent;
UPROPERTY(VisibleAnywhere)
float ForwardSpeed = 0.0f;
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Lidar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Lidar.cpp
index 1e692b9fa..215e0edeb 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Lidar.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Lidar.cpp
@@ -94,6 +94,7 @@ void ALidar::ReadPoints(const float DeltaTime)
}
const float HorizontalAngle = std::fmod(CurrentHorizontalAngle + AngleDistanceOfTick, 360.0f);
+ LidarMeasurement.SetFrameNumber(GFrameCounter);
LidarMeasurement.SetHorizontalAngle(HorizontalAngle);
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/LidarMeasurement.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/LidarMeasurement.h
index 869977125..534d6c28f 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/LidarMeasurement.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/LidarMeasurement.h
@@ -15,6 +15,7 @@
/// The header consists of an array of uint32's in the following layout
///
/// {
+/// Frame number (uint64)
/// Horizontal angle (float),
/// Channel count,
/// Point count of channel 0,
@@ -37,8 +38,8 @@ public:
explicit FLidarMeasurement(uint32 SensorId = 0u, uint32 ChannelCount = 0u)
: SensorId(SensorId)
{
- Header.AddDefaulted(2u + ChannelCount);
- Header[1] = ChannelCount;
+ Header.AddDefaulted(4u + ChannelCount);
+ Header[3] = ChannelCount;
}
FLidarMeasurement &operator=(FLidarMeasurement &&Other)
@@ -50,31 +51,36 @@ public:
return *this;
}
+ void SetFrameNumber(uint64 FrameNumber)
+ {
+ std::memcpy(Header.GetData(), reinterpret_cast(&FrameNumber), 2u);
+ }
+
float GetHorizontalAngle() const
{
- return reinterpret_cast(Header[0]);
+ return reinterpret_cast(Header[2]);
}
void SetHorizontalAngle(float HorizontalAngle)
{
- Header[0] = reinterpret_cast(HorizontalAngle);
+ Header[2] = reinterpret_cast(HorizontalAngle);
}
uint32 GetChannelCount() const
{
- return Header[1];
+ return Header[3];
}
void Reset(uint32 TotalPointCount)
{
- std::memset(Header.GetData() + 2u, 0, sizeof(uint32) * GetChannelCount());
+ std::memset(Header.GetData() + 4u, 0, sizeof(uint32) * GetChannelCount());
Points.Reset(3u * TotalPointCount);
}
void WritePoint(uint32 Channel, const FVector &Point)
{
- check(Header[1] > Channel);
- Header[2u + Channel] += 1u;
+ check(Header[3] > Channel);
+ Header[4u + Channel] += 1u;
constexpr float TO_METERS = 1e-2f;
Points.Emplace(TO_METERS * Point.X);
Points.Emplace(TO_METERS * Point.Y);
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp
index 30e7e57cf..712cc5164 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.cpp
@@ -8,41 +8,68 @@
#include "SceneCaptureCamera.h"
#include "Sensor/SensorDataView.h"
+#include "Settings/CarlaSettings.h"
#include "Components/DrawFrustumComponent.h"
#include "Components/SceneCaptureComponent2D.h"
#include "Components/StaticMeshComponent.h"
+#include "ConstructorHelpers.h"
+#include "CoreGlobals.h"
#include "Engine/CollisionProfile.h"
#include "Engine/TextureRenderTarget2D.h"
-#include "HighResScreenshot.h"
+#include "Game/CarlaGameInstance.h"
+#include "Kismet/KismetSystemLibrary.h"
#include "Materials/Material.h"
-#include "Paths.h"
+#include
+
+// =============================================================================
+// -- Local static variables ---------------------------------------------------
+// =============================================================================
static constexpr auto DEPTH_MAT_PATH =
#if PLATFORM_LINUX
- TEXT("Material'/Carla/PostProcessingMaterials/DepthEffectMaterial_GLSL.DepthEffectMaterial_GLSL'");
+ TEXT("Material'/Carla/PostProcessingMaterials/DepthEffectMaterial_GLSL.DepthEffectMaterial_GLSL'");
#elif PLATFORM_WINDOWS
- TEXT("Material'/Carla/PostProcessingMaterials/DepthEffectMaterial.DepthEffectMaterial'");
+ TEXT("Material'/Carla/PostProcessingMaterials/DepthEffectMaterial.DepthEffectMaterial'");
#else
# error No depth material defined for this platform
#endif
static constexpr auto SEMANTIC_SEGMENTATION_MAT_PATH =
- TEXT("Material'/Carla/PostProcessingMaterials/GTMaterial.GTMaterial'");
+ TEXT("Material'/Carla/PostProcessingMaterials/GTMaterial.GTMaterial'");
+
+// =============================================================================
+// -- Local static methods and types -------------------------------------------
+// =============================================================================
+
+struct FImageHeaderData
+{
+ uint64 FrameNumber;
+ uint32 Width;
+ uint32 Height;
+ uint32 Type;
+ float FOV;
+};
static void RemoveShowFlags(FEngineShowFlags &ShowFlags);
-ASceneCaptureCamera::ASceneCaptureCamera(const FObjectInitializer& ObjectInitializer) :
- Super(ObjectInitializer),
- SizeX(720u),
- SizeY(512u),
- PostProcessEffect(EPostProcessEffect::SceneFinal)
+// =============================================================================
+// -- ASceneCaptureCamera ------------------------------------------------------
+// =============================================================================
+
+uint32 ASceneCaptureCamera::NumSceneCapture = 0;
+
+ASceneCaptureCamera::ASceneCaptureCamera(const FObjectInitializer &ObjectInitializer)
+ : Super(ObjectInitializer),
+ SizeX(720u),
+ SizeY(512u),
+ PostProcessEffect(EPostProcessEffect::SceneFinal)
{
PrimaryActorTick.bCanEverTick = true;
PrimaryActorTick.TickGroup = TG_PrePhysics;
- MeshComp = CreateDefaultSubobject(TEXT("CamMesh0"));
+ MeshComp = CreateDefaultSubobject(TEXT("CamMesh"));
MeshComp->SetCollisionProfileName(UCollisionProfile::NoCollision_ProfileName);
@@ -51,28 +78,34 @@ ASceneCaptureCamera::ASceneCaptureCamera(const FObjectInitializer& ObjectInitial
MeshComp->PostPhysicsComponentTick.bCanEverTick = false;
RootComponent = MeshComp;
- DrawFrustum = CreateDefaultSubobject(TEXT("DrawFrust0"));
+ DrawFrustum = CreateDefaultSubobject(TEXT("DrawFrust"));
DrawFrustum->bIsEditorOnly = true;
DrawFrustum->SetupAttachment(MeshComp);
- CaptureRenderTarget = CreateDefaultSubobject(TEXT("CaptureRenderTarget0"));
- #if WITH_EDITORONLY_DATA
- CaptureRenderTarget->CompressionNoAlpha = true;
- CaptureRenderTarget->MipGenSettings = TextureMipGenSettings::TMGS_NoMipmaps;
- #endif
+ CaptureRenderTarget = CreateDefaultSubobject(
+ FName(*FString::Printf(TEXT("CaptureRenderTarget%d"), NumSceneCapture)));
+#if WITH_EDITORONLY_DATA
+ CaptureRenderTarget->CompressionNoAlpha = true;
+ CaptureRenderTarget->MipGenSettings = TextureMipGenSettings::TMGS_NoMipmaps;
+ CaptureRenderTarget->bUseLegacyGamma = false;
+#endif
CaptureRenderTarget->CompressionSettings = TextureCompressionSettings::TC_Default;
- CaptureRenderTarget->SRGB=0;
+ CaptureRenderTarget->SRGB = false;
CaptureRenderTarget->bAutoGenerateMips = false;
CaptureRenderTarget->AddressX = TextureAddress::TA_Clamp;
CaptureRenderTarget->AddressY = TextureAddress::TA_Clamp;
- CaptureComponent2D = CreateDefaultSubobject(TEXT("SceneCaptureComponent2D"));
+ CaptureComponent2D = CreateDefaultSubobject(
+ TEXT("SceneCaptureComponent2D"));
CaptureComponent2D->SetupAttachment(MeshComp);
-
+
// Load post-processing materials.
- static ConstructorHelpers::FObjectFinder DEPTH(DEPTH_MAT_PATH);
+ static ConstructorHelpers::FObjectFinder DEPTH(
+ DEPTH_MAT_PATH);
PostProcessDepth = DEPTH.Object;
- static ConstructorHelpers::FObjectFinder SEMANTIC_SEGMENTATION(SEMANTIC_SEGMENTATION_MAT_PATH);
+ static ConstructorHelpers::FObjectFinder SEMANTIC_SEGMENTATION(
+ SEMANTIC_SEGMENTATION_MAT_PATH);
PostProcessSemanticSegmentation = SEMANTIC_SEGMENTATION.Object;
+ NumSceneCapture++;
}
void ASceneCaptureCamera::PostActorCreated()
@@ -81,18 +114,23 @@ void ASceneCaptureCamera::PostActorCreated()
// no need load the editor mesh when there is no editor
#if WITH_EDITOR
- if(MeshComp)
+ if (MeshComp)
{
if (!IsRunningCommandlet())
{
- if( !MeshComp->GetStaticMesh())
+ if (!MeshComp->GetStaticMesh())
{
- UStaticMesh* CamMesh = LoadObject(NULL, TEXT("/Engine/EditorMeshes/MatineeCam_SM.MatineeCam_SM"), NULL, LOAD_None, NULL);
+ UStaticMesh *CamMesh = LoadObject(
+ NULL,
+ TEXT("/Engine/EditorMeshes/MatineeCam_SM.MatineeCam_SM"),
+ NULL,
+ LOAD_None,
+ NULL);
MeshComp->SetStaticMesh(CamMesh);
}
}
}
-#endif // WITH_EDITOR
+#endif // WITH_EDITOR
// Sync component with CameraActor frustum settings.
UpdateDrawFrustum();
@@ -105,49 +143,104 @@ void ASceneCaptureCamera::BeginPlay()
// Setup render target.
const bool bInForceLinearGamma = bRemovePostProcessing;
CaptureRenderTarget->InitCustomFormat(SizeX, SizeY, PF_B8G8R8A8, bInForceLinearGamma);
-
+ if (!IsValid(CaptureComponent2D) || CaptureComponent2D->IsPendingKill())
+ {
+ CaptureComponent2D = NewObject(this, TEXT("SceneCaptureComponent2D"));
+ CaptureComponent2D->SetupAttachment(MeshComp);
+ }
CaptureComponent2D->Deactivate();
CaptureComponent2D->TextureTarget = CaptureRenderTarget;
- // Setup camera post-processing.
- if (PostProcessEffect != EPostProcessEffect::None) {
- CaptureComponent2D->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR; //HD is much slower!
+ // Setup camera post-processing depending on the quality level:
+ const UCarlaGameInstance *GameInstance = Cast(GetWorld()->GetGameInstance());
+ check(GameInstance != nullptr);
+ const UCarlaSettings &CarlaSettings = GameInstance->GetCarlaSettings();
+ switch (PostProcessEffect)
+ {
+ case EPostProcessEffect::None:
+ break;
+ case EPostProcessEffect::SceneFinal:
+ {
+ // We set LDR for high quality because it will include post-fx and HDR for
+ // low quality to avoid high contrast.
+ switch (CarlaSettings.GetQualitySettingsLevel())
+ {
+ case EQualitySettingsLevel::Low:
+ CaptureComponent2D->CaptureSource = ESceneCaptureSource::SCS_SceneColorHDRNoAlpha;
+ break;
+ default:
+ // LDR is faster than HDR (smaller bitmap array).
+ CaptureComponent2D->CaptureSource = ESceneCaptureSource::SCS_FinalColorLDR;
+ break;
+ }
+ break;
+ }
+ default:
+ CaptureComponent2D->CaptureSource = SCS_FinalColorLDR;
+ break;
}
- if (bRemovePostProcessing) {
+
+ if (bRemovePostProcessing)
+ {
RemoveShowFlags(CaptureComponent2D->ShowFlags);
}
- if (PostProcessEffect == EPostProcessEffect::Depth) {
+
+ if (PostProcessEffect == EPostProcessEffect::Depth)
+ {
CaptureComponent2D->PostProcessSettings.AddBlendable(PostProcessDepth, 1.0f);
- } else if (PostProcessEffect == EPostProcessEffect::SemanticSegmentation) {
+ }
+ else if (PostProcessEffect == EPostProcessEffect::SemanticSegmentation)
+ {
CaptureComponent2D->PostProcessSettings.AddBlendable(PostProcessSemanticSegmentation, 1.0f);
}
CaptureComponent2D->UpdateContent();
CaptureComponent2D->Activate();
+ // Make sure that there is enough time in the render queue.
+ UKismetSystemLibrary::ExecuteConsoleCommand(
+ GetWorld(),
+ FString("g.TimeoutForBlockOnRenderFence 300000"));
+
Super::BeginPlay();
}
+void ASceneCaptureCamera::EndPlay(const EEndPlayReason::Type EndPlayReason)
+{
+ if (NumSceneCapture != 0)
+ {
+ NumSceneCapture = 0;
+ }
+}
+
void ASceneCaptureCamera::Tick(const float DeltaSeconds)
{
Super::Tick(DeltaSeconds);
- if(IsVulkanPlatform(GMaxRHIShaderPlatform))
+
+ const auto FrameNumber = GFrameCounter;
+
+ if (IsVulkanPlatform(GMaxRHIShaderPlatform))
{
- auto fn = [=](FRHICommandListImmediate& RHICmdList){WritePixelsNonBlocking(DeltaSeconds,RHICmdList);};
+ auto fn = [=](FRHICommandListImmediate &RHICmdList) {
+ WritePixelsNonBlocking(FrameNumber, RHICmdList);
+ };
ENQUEUE_UNIQUE_RENDER_COMMAND_ONEPARAMETER(
- FWritePixelsNonBlocking,
- decltype(fn),write_function_vulkan,fn,
- {
- write_function_vulkan(RHICmdList);
- });
- } else
- {
- auto fn = [=](){WritePixels(DeltaSeconds);};
- ENQUEUE_UNIQUE_RENDER_COMMAND_ONEPARAMETER(
- FWritePixels,
- decltype(fn),write_function,fn,
+ FWritePixelsNonBlocking,
+ decltype(fn), write_function_vulkan, fn,
{
- write_function();
+ write_function_vulkan(RHICmdList);
+ });
+ }
+ else
+ {
+ auto fn = [=]() {
+ WritePixels(FrameNumber);
+ };
+ ENQUEUE_UNIQUE_RENDER_COMMAND_ONEPARAMETER(
+ FWritePixels,
+ decltype(fn), write_function, fn,
+ {
+ write_function();
});
}
}
@@ -168,7 +261,8 @@ void ASceneCaptureCamera::SetPostProcessEffect(EPostProcessEffect otherPostProce
{
PostProcessEffect = otherPostProcessEffect;
auto &PostProcessSettings = CaptureComponent2D->PostProcessSettings;
- if (PostProcessEffect != EPostProcessEffect::SceneFinal) {
+ if (PostProcessEffect != EPostProcessEffect::SceneFinal)
+ {
PostProcessSettings.bOverride_AutoExposureMethod = false;
PostProcessSettings.bOverride_AutoExposureMinBrightness = false;
PostProcessSettings.bOverride_AutoExposureMaxBrightness = false;
@@ -192,7 +286,8 @@ void ASceneCaptureCamera::Set(const UCameraDescription &CameraDescription)
{
Super::Set(CameraDescription);
- if (CameraDescription.bOverrideCameraPostProcessParameters) {
+ if (CameraDescription.bOverrideCameraPostProcessParameters)
+ {
auto &Override = CameraDescription.CameraPostProcessParameters;
auto &PostProcessSettings = CaptureComponent2D->PostProcessSettings;
PostProcessSettings.bOverride_AutoExposureMethod = true;
@@ -211,13 +306,15 @@ void ASceneCaptureCamera::Set(const UCameraDescription &CameraDescription)
bool ASceneCaptureCamera::ReadPixels(TArray &BitMap) const
{
- if(!CaptureRenderTarget)
+ if (!CaptureRenderTarget)
{
- UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target"));
- return false;
+ UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target"));
+ return false;
}
- FTextureRenderTargetResource* RTResource = CaptureRenderTarget->GameThread_GetRenderTargetResource();
- if (RTResource == nullptr) {
+ FTextureRenderTargetResource *RTResource =
+ CaptureRenderTarget->GameThread_GetRenderTargetResource();
+ if (RTResource == nullptr)
+ {
UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target"));
return false;
}
@@ -226,105 +323,116 @@ bool ASceneCaptureCamera::ReadPixels(TArray &BitMap) const
return RTResource->ReadPixels(BitMap, ReadPixelFlags);
}
-void ASceneCaptureCamera::WritePixelsNonBlocking(float DeltaTime, FRHICommandListImmediate& rhi_cmd_list) const
- {
+void ASceneCaptureCamera::WritePixelsNonBlocking(
+ const uint64 FrameNumber,
+ FRHICommandListImmediate &rhi_cmd_list) const
+{
check(IsInRenderingThread());
- if(!CaptureRenderTarget)
+ if (!CaptureRenderTarget)
{
- UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target"));
- return ;
+ UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target"));
+ return;
}
- FTextureRenderTarget2DResource* RenderResource = (FTextureRenderTarget2DResource*)CaptureRenderTarget->Resource;
+ FTextureRenderTarget2DResource *RenderResource =
+ (FTextureRenderTarget2DResource *) CaptureRenderTarget->Resource;
FTextureRHIParamRef texture = RenderResource->GetRenderTargetTexture();
- if(!texture)
+ if (!texture)
{
UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render target texture"));
return;
}
- struct {
- uint32 Width;
- uint32 Height;
- uint32 Type;
- float FOV;
- } ImageHeader = {
+ FImageHeaderData ImageHeader = {
+ FrameNumber,
SizeX,
SizeY,
PostProcessEffect::ToUInt(PostProcessEffect),
CaptureComponent2D->FOVAngle
};
-
- struct FReadSurfaceContext
- {
- FRenderTarget* SrcRenderTarget;
- TArray* OutData;
- FIntRect Rect;
- FReadSurfaceDataFlags Flags;
- };
- TArray Pixels;
+
+ TArray Pixels;
rhi_cmd_list.ReadSurfaceData(
- texture,
- FIntRect(0, 0, RenderResource->GetSizeXY().X, RenderResource->GetSizeXY().Y),
- Pixels,
- FReadSurfaceDataFlags(RCM_UNorm, CubeFace_MAX)
- );
+ 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);
-
+ GetId(),
+ FReadOnlyBufferView{reinterpret_cast(&ImageHeader), sizeof(ImageHeader)},
+ FReadOnlyBufferView{Pixels});
+ WriteSensorData(DataView);
}
-void ASceneCaptureCamera::WritePixels(float DeltaTime) const
+void ASceneCaptureCamera::WritePixels(const uint64 FrameNumber) const
{
FRHITexture2D *texture = CaptureRenderTarget->GetRenderTargetResource()->GetRenderTargetTexture();
- if(!texture)
+ if (!texture)
{
- UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render texture"));
- return ;
+ UE_LOG(LogCarla, Error, TEXT("SceneCaptureCamera: Missing render texture"));
+ return;
}
+ const uint32 num_bytes_per_pixel = 4; // PF_R8G8B8A8
const uint32 width = texture->GetSizeX();
- uint32 height = texture->GetSizeY();
- uint32 stride;
- uint8 *src = reinterpret_cast(RHILockTexture2D(texture, 0, RLM_ReadOnly, stride, false));
- struct {
- uint32 Width;
- uint32 Height;
- uint32 Type;
- float FOV;
- } ImageHeader = {
- SizeX,
- SizeY,
+ const uint32 height = texture->GetSizeY();
+ const uint32 dest_stride = width * height * num_bytes_per_pixel;
+ uint32 src_stride;
+ uint8 *src = reinterpret_cast(
+ RHILockTexture2D(texture, 0, RLM_ReadOnly, src_stride, false));
+ FImageHeaderData ImageHeader = {
+ FrameNumber,
+ width,
+ height,
PostProcessEffect::ToUInt(PostProcessEffect),
CaptureComponent2D->FOVAngle
};
- FSensorDataView DataView(
- GetId(),
- FReadOnlyBufferView{reinterpret_cast(&ImageHeader), sizeof(ImageHeader)},
- FReadOnlyBufferView{src,stride*height}
- );
+
+ std::unique_ptr dest = nullptr;
+ // Direct 3D uses additional rows in the buffer,so we need check the result
+ // stride from the lock:
+ if (IsD3DPlatform(GMaxRHIShaderPlatform, false) && (dest_stride != src_stride))
+ {
+ const uint32 copy_row_stride = width * num_bytes_per_pixel;
+ dest = std::make_unique(dest_stride);
+ // Copy per row
+ uint8 *dest_row = dest.get();
+ uint8 *src_row = src;
+ for (uint32 Row = 0; Row < height; ++Row)
+ {
+ FMemory::Memcpy(dest_row, src_row, copy_row_stride);
+ dest_row += copy_row_stride;
+ src_row += src_stride;
+ }
+ src = dest.get();
+ }
+
+ const FSensorDataView DataView(
+ GetId(),
+ FReadOnlyBufferView{reinterpret_cast(&ImageHeader), sizeof(ImageHeader)},
+ FReadOnlyBufferView{src, dest_stride});
WriteSensorData(DataView);
RHIUnlockTexture2D(texture, 0, false);
}
-
void ASceneCaptureCamera::UpdateDrawFrustum()
{
- if(DrawFrustum && CaptureComponent2D)
+ if (DrawFrustum && CaptureComponent2D)
{
DrawFrustum->FrustumStartDist = GNearClippingPlane;
- // 1000 is the default frustum distance, ideally this would be infinite but that might cause rendering issues
- DrawFrustum->FrustumEndDist = (CaptureComponent2D->MaxViewDistanceOverride > DrawFrustum->FrustumStartDist)
+ // 1000 is the default frustum distance, ideally this would be infinite but
+ // that might cause rendering issues.
+ DrawFrustum->FrustumEndDist =
+ (CaptureComponent2D->MaxViewDistanceOverride > DrawFrustum->FrustumStartDist)
? CaptureComponent2D->MaxViewDistanceOverride : 1000.0f;
DrawFrustum->FrustumAngle = CaptureComponent2D->FOVAngle;
- //DrawFrustum->FrustumAspectRatio = CaptureComponent2D->AspectRatio;
}
}
+// =============================================================================
+// -- Local static functions implementations -----------------------------------
+// =============================================================================
+
// Remove the show flags that might interfere with post-processing effects like
// depth and semantic segmentation.
static void RemoveShowFlags(FEngineShowFlags &ShowFlags)
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h
index c61adb8f4..633d62bed 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureCamera.h
@@ -37,7 +37,7 @@ protected:
public:
virtual void BeginPlay() override;
-
+ virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
virtual void Tick(float DeltaSeconds) override;
uint32 GetImageSizeX() const
@@ -68,13 +68,21 @@ public:
void Set(const UCameraDescription &CameraDescription);
bool ReadPixels(TArray &BitMap) const;
-
+
+protected:
+ static uint32 NumSceneCapture;
private:
- ///Read the camera buffer and write it to the client with no lock of the resources (for Vulkan API)
- void WritePixelsNonBlocking(float DeltaTime,FRHICommandListImmediate& rhi_cmd_list) const;
- ///Read the camera buffer and write it to the client with opengl or direct3d
- void WritePixels(float DeltaTime) const;
+
+ /// Read the camera buffer and write it to the client with no lock of the
+ /// resources (for Vulkan API).
+ void WritePixelsNonBlocking(
+ uint64 FrameNumber,
+ FRHICommandListImmediate& rhi_cmd_list) const;
+
+ /// Read the camera buffer and write it to the client with opengl or direct3d.
+ void WritePixels(uint64 FrameNumber) const;
+
/// Used to synchronize the DrawFrustumComponent with the
/// SceneCaptureComponent2D settings.
void UpdateDrawFrustum();
@@ -97,7 +105,7 @@ private:
UDrawFrustumComponent* DrawFrustum;
/** Render target necessary for scene capture */
- UPROPERTY(Transient)
+ UPROPERTY()
UTextureRenderTarget2D* CaptureRenderTarget;
/** Scene capture component. */
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureToDiskCamera.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureToDiskCamera.cpp
index 0303c2b01..482a25f47 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureToDiskCamera.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/SceneCaptureToDiskCamera.cpp
@@ -12,7 +12,7 @@
ASceneCaptureToDiskCamera::ASceneCaptureToDiskCamera(const FObjectInitializer& ObjectInitializer) :
Super(ObjectInitializer),
- SaveToFolder(FPaths::Combine(FPaths::ProjectSavedDir(), "SceneCaptures")),
+ SaveToFolder(*FPaths::Combine(FPaths::ProjectSavedDir(), TEXT("SceneCaptures"))),
FileName("capture_%05d.png") {}
void ASceneCaptureToDiskCamera::BeginPlay()
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp
index 5ecbab6c9..23bea5866 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Server/CarlaEncoder.cpp
@@ -106,11 +106,13 @@ void FCarlaEncoder::Encode(
const ACarlaPlayerState &PlayerState,
carla_measurements &Data)
{
+ Data.frame_number = PlayerState.GetFrameNumber();
Data.platform_timestamp = PlayerState.GetPlatformTimeStamp();
Data.game_timestamp = PlayerState.GetGameTimeStamp();
auto &Player = Data.player_measurements;
::Encode(PlayerState.GetTransform(), Player.transform);
- ::Encode(PlayerState.GetBoundsExtent() * TO_METERS, Player.box_extent);
+ ::Encode(PlayerState.GetBoundingBoxTransform(), Player.bounding_box.transform);
+ ::Encode(PlayerState.GetBoundingBoxExtent() * TO_METERS, Player.bounding_box.extent);
::Encode(PlayerState.GetAcceleration() * TO_METERS, Player.acceleration);
Player.forward_speed = PlayerState.GetForwardSpeed() * TO_METERS;
Player.collision_vehicles = PlayerState.GetCollisionIntensityCars() * TO_METERS;
@@ -204,17 +206,18 @@ void FCarlaEncoder::Visit(const UTrafficSignAgentComponent &Agent)
void FCarlaEncoder::Visit(const UVehicleAgentComponent &Agent)
{
- auto &Vehicle = Agent.GetVehicle();
- ::Encode(Vehicle.GetVehicleTransform(), Data.transform);
+ ::Encode(Agent.GetTransform(), Data.transform);
Data.type = CARLA_SERVER_AGENT_VEHICLE;
- Data.forward_speed = Vehicle.GetVehicleForwardSpeed() * TO_METERS;
- ::Encode(Vehicle.GetVehicleBoundsExtent() * TO_METERS, Data.box_extent);
+ Data.forward_speed = Agent.GetForwardSpeed() * TO_METERS;
+ ::Encode(Agent.GetBoundingBoxTransform(), Data.bounding_box.transform);
+ ::Encode(Agent.GetBoundingBoxExtent() * TO_METERS, Data.bounding_box.extent);
}
void FCarlaEncoder::Visit(const UWalkerAgentComponent &Agent)
{
- ::Encode(Agent.GetComponentTransform(), Data.transform);
+ ::Encode(Agent.GetTransform(), Data.transform);
Data.type = CARLA_SERVER_AGENT_PEDESTRIAN;
Data.forward_speed = Agent.GetForwardSpeed() * TO_METERS;
- ::Encode(Agent.GetBoundingBoxExtent() * TO_METERS, Data.box_extent);
+ ::Encode(Agent.GetBoundingBoxTransform(), Data.bounding_box.transform);
+ ::Encode(Agent.GetBoundingBoxExtent() * TO_METERS, Data.bounding_box.extent);
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp
index 24f80747c..9c2dc63df 100755
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.cpp
@@ -122,10 +122,7 @@ static void LoadSettingsFromConfig(
// QualitySettings.
FString sQualityLevel;
ConfigFile.GetString(S_CARLA_QUALITYSETTINGS, TEXT("QualityLevel"), sQualityLevel);
- if(!Settings.SetQualitySettingsLevel(UQualitySettings::FromString(sQualityLevel)))
- {
- //error
- }
+ Settings.SetQualitySettingsLevel(UQualitySettings::FromString(sQualityLevel));
// Sensors.
FString Sensors;
@@ -176,17 +173,9 @@ FString UQualitySettings::ToString(EQualitySettingsLevel QualitySettingsLevel)
return ptr->GetNameStringByIndex(static_cast(QualitySettingsLevel));
}
-bool UCarlaSettings::SetQualitySettingsLevel(EQualitySettingsLevel newQualityLevel)
+void UCarlaSettings::SetQualitySettingsLevel(EQualitySettingsLevel newQualityLevel)
{
- if(newQualityLevel==EQualitySettingsLevel::None)
- {
- UE_LOG(LogCarla ,Warning, TEXT("Quality Settings Level not set!"));
- return false;
- }
-
QualitySettingsLevel = newQualityLevel;
-
- return true;
}
void UCarlaSettings::LoadSettings()
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h
index bd5d59aed..c0772ff83 100755
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettings.h
@@ -5,13 +5,11 @@
// For a copy, see .
#pragma once
-
+#include "Engine/StaticMesh.h"
#include "WeatherDescription.h"
-
-#include "UObject/NoExportTypes.h"
-
#include "CarlaSettings.generated.h"
+
UENUM(BlueprintType)
enum class EQualitySettingsLevel : uint8
{
@@ -42,7 +40,7 @@ public:
};
class USensorDescription;
-struct FStaticMaterial;
+
/** Global settings for CARLA.
* Setting object used to hold both config settings and editable ones in one place
* To ensure the settings are saved to the specified config file make sure to add
@@ -57,12 +55,12 @@ public:
/**
* Sets the new quality settings level and make changes in the game related to it.
- * Returns the result of the operation.
* @note This will not apply the quality settings. Use ApplyQualitySettings functions instead
* @param newQualityLevel Store the new quality
*/
UFUNCTION(BlueprintCallable, Category="CARLA Settings")
- bool SetQualitySettingsLevel(EQualitySettingsLevel newQualityLevel);
+ void SetQualitySettingsLevel(EQualitySettingsLevel newQualityLevel);
+
/** @return current quality settings level (could not be applied yet) */
UFUNCTION(BlueprintCallable, Category="CARLA Settings")
EQualitySettingsLevel GetQualitySettingsLevel() const { return QualitySettingsLevel; }
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp
index 179d457b9..91749a64a 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.cpp
@@ -1,5 +1,5 @@
#include "Carla.h"
-#include "Engine/World.h"
+
#include "Game/CarlaGameModeBase.h"
#include "Settings/CarlaSettings.h"
#include "CarlaSettingsDelegate.h"
@@ -10,6 +10,7 @@
#include "Engine/StaticMesh.h"
#include "Engine/PostProcessVolume.h"
#include "UObjectIterator.h"
+#include "Async.h"
///quality settings configuration between runs
EQualitySettingsLevel UCarlaSettingsDelegate::AppliedLowPostResetQualitySettingsLevel = EQualitySettingsLevel::Epic;
@@ -21,8 +22,7 @@ UCarlaSettingsDelegate::UCarlaSettingsDelegate() :
void UCarlaSettingsDelegate::Reset()
{
- LaunchEpicQualityCommands(GetLocalWorld());
- AppliedLowPostResetQualitySettingsLevel = EQualitySettingsLevel::Epic;
+ AppliedLowPostResetQualitySettingsLevel = EQualitySettingsLevel::None;
}
void UCarlaSettingsDelegate::RegisterSpawnHandler(UWorld *InWorld)
@@ -62,7 +62,8 @@ void UCarlaSettingsDelegate::ApplyQualitySettingsLevelPostRestart()
{
CheckCarlaSettings(nullptr);
UWorld *InWorld = CarlaSettings->GetWorld();
- EQualitySettingsLevel QualitySettingsLevel = CarlaSettings->GetQualitySettingsLevel();
+
+ EQualitySettingsLevel QualitySettingsLevel = CarlaSettings->GetQualitySettingsLevel();
if(AppliedLowPostResetQualitySettingsLevel==QualitySettingsLevel) return;
switch(QualitySettingsLevel)
@@ -70,7 +71,7 @@ void UCarlaSettingsDelegate::ApplyQualitySettingsLevelPostRestart()
case EQualitySettingsLevel::Low:
{
//execute tweaks for quality
- LaunchLowQualityCommands(InWorld);
+ LaunchLowQualityCommands(InWorld);
//iterate all directional lights, deactivate shadows
SetAllLights(InWorld,CarlaSettings->LowLightFadeDistance,false,true);
//Set all the roads the low quality materials
@@ -181,45 +182,49 @@ void UCarlaSettingsDelegate::LaunchLowQualityCommands(UWorld * world) const
void UCarlaSettingsDelegate::SetAllRoads(UWorld* world, const float max_draw_distance, const TArray &road_pieces_materials) const
{
- TArray actors;
- UGameplayStatics::GetAllActorsWithTag(world, UCarlaSettings::CARLA_ROAD_TAG,actors);
-
- for(int32 i=0; iIsPendingKillPending()) continue;
- TArray components = actors[i]->GetComponentsByClass(UStaticMeshComponent::StaticClass());
- for(int32 j=0; j(components[j]);
- if(staticmeshcomponent)
- {
- staticmeshcomponent->bAllowCullDistanceVolume = (max_draw_distance>0);
- staticmeshcomponent->bUseAsOccluder = false;
- staticmeshcomponent->LDMaxDrawDistance = max_draw_distance;
- staticmeshcomponent->CastShadow = (max_draw_distance==0);
- if(road_pieces_materials.Num()>0)
- {
- TArray meshslotsnames = staticmeshcomponent->GetMaterialSlotNames();
- for(int32 k=0; kIsPendingKill()) return;
+ AsyncTask(ENamedThreads::GameThread, [=](){
+ if(!world||!IsValid(world)||world->IsPendingKill()) return;
+ TArray actors;
+ UGameplayStatics::GetAllActorsWithTag(world, UCarlaSettings::CARLA_ROAD_TAG,actors);
+
+ for(int32 i=0; iIsPendingKillPending()) continue;
+ TArray components = actors[i]->GetComponentsByClass(UStaticMeshComponent::StaticClass());
+ for(int32 j=0; j(components[j]);
+ if(staticmeshcomponent)
+ {
+ staticmeshcomponent->bAllowCullDistanceVolume = (max_draw_distance>0);
+ staticmeshcomponent->bUseAsOccluder = false;
+ staticmeshcomponent->LDMaxDrawDistance = max_draw_distance;
+ staticmeshcomponent->CastShadow = (max_draw_distance==0);
+ if(road_pieces_materials.Num()>0)
{
- const FName &slotname = meshslotsnames[k];
- road_pieces_materials.ContainsByPredicate(
- [staticmeshcomponent,slotname](const FStaticMaterial& material)
+ TArray meshslotsnames = staticmeshcomponent->GetMaterialSlotNames();
+ for(int32 k=0; kSetMaterial(
- staticmeshcomponent->GetMaterialIndex(slotname),
- material.MaterialInterface
- );
- return true;
- } else return false;
- });
+ if(material.MaterialSlotName.IsEqual(slotname))
+ {
+ staticmeshcomponent->SetMaterial(
+ staticmeshcomponent->GetMaterialIndex(slotname),
+ material.MaterialInterface
+ );
+ return true;
+ } else return false;
+ });
+ }
}
- }
- }
- }
- }
+ }
+ }
+ }
+ }); //,DELAY_TIME_TO_SET_ALL_ROADS, false);
}
void UCarlaSettingsDelegate::SetActorComponentsDrawDistance(AActor* actor, const float max_draw_distance) const
@@ -243,20 +248,24 @@ void UCarlaSettingsDelegate::SetActorComponentsDrawDistance(AActor* actor, const
void UCarlaSettingsDelegate::SetAllActorsDrawDistance(UWorld* world, const float max_draw_distance) const
{
///@TODO: use semantics to grab all actors by type (vehicles,ground,people,props) and set different distances configured in the global properties
- TArray actors;
- #define _MAX_SCALE_SIZE 50.0f
- //set the lower quality - max draw distance
- UGameplayStatics::GetAllActorsOfClass(world, AActor::StaticClass(),actors);
- for(int32 i=0; iIsPendingKillPending() ||
- actors[i]->ActorHasTag(UCarlaSettings::CARLA_ROAD_TAG) ||
- actors[i]->ActorHasTag(UCarlaSettings::CARLA_SKY_TAG)
- ){
- continue;
- }
- SetActorComponentsDrawDistance(actors[i], max_draw_distance);
- }
+ if(!world||!IsValid(world)||world->IsPendingKill()) return;
+ AsyncTask(ENamedThreads::GameThread, [=](){
+ if(!world||!IsValid(world)||world->IsPendingKill()) return;
+ TArray actors;
+ #define _MAX_SCALE_SIZE 50.0f
+ //set the lower quality - max draw distance
+ UGameplayStatics::GetAllActorsOfClass(world, AActor::StaticClass(),actors);
+ for(int32 i=0; iIsPendingKillPending() ||
+ actors[i]->ActorHasTag(UCarlaSettings::CARLA_ROAD_TAG) ||
+ actors[i]->ActorHasTag(UCarlaSettings::CARLA_SKY_TAG)
+ ){
+ continue;
+ }
+ SetActorComponentsDrawDistance(actors[i], max_draw_distance);
+ }
+ });
}
@@ -266,12 +275,12 @@ void UCarlaSettingsDelegate::SetPostProcessEffectsEnabled(UWorld* world, const b
UGameplayStatics::GetAllActorsOfClass(world, APostProcessVolume::StaticClass(), actors);
for(int32 i=0; iIsPendingKillPending()) continue;
- APostProcessVolume* postprocessvolume = Cast(actors[i]);
- if(postprocessvolume)
- {
- postprocessvolume->bEnabled = enabled;
- }
+ if(!IsValid(actors[i]) || actors[i]->IsPendingKillPending()) continue;
+ APostProcessVolume* postprocessvolume = Cast(actors[i]);
+ if(postprocessvolume)
+ {
+ postprocessvolume->bEnabled = enabled;
+ }
}
}
@@ -318,21 +327,26 @@ void UCarlaSettingsDelegate::LaunchEpicQualityCommands(UWorld* world) const
void UCarlaSettingsDelegate::SetAllLights(UWorld* world, const float max_distance_fade, const bool cast_shadows, const bool hide_non_directional) const
{
- TArray actors;
- UGameplayStatics::GetAllActorsOfClass(world, ALight::StaticClass(), actors);
- for(int32 i=0;iIsPendingKillPending()) continue;
- //tweak directional lights
- ADirectionalLight* directionallight = Cast(actors[i]);
- if(directionallight)
+ if(!world||!IsValid(world)||world->IsPendingKill()) return;
+ AsyncTask(ENamedThreads::GameThread, [=](){
+ if(!world||!IsValid(world)||world->IsPendingKill()) return;
+ TArray actors;
+ UGameplayStatics::GetAllActorsOfClass(world, ALight::StaticClass(), actors);
+ for(int32 i=0;iSetCastShadows(cast_shadows);
- directionallight->SetLightFunctionFadeDistance(max_distance_fade);
- continue;
+ if(!IsValid(actors[i]) || actors[i]->IsPendingKillPending()) continue;
+ //tweak directional lights
+ ADirectionalLight* directionallight = Cast(actors[i]);
+ if(directionallight)
+ {
+ directionallight->SetCastShadows(cast_shadows);
+ directionallight->SetLightFunctionFadeDistance(max_distance_fade);
+ continue;
+ }
+ //disable any other type of light
+ actors[i]->SetActorHiddenInGame(hide_non_directional);
}
- //disable any other type of light
- actors[i]->SetActorHiddenInGame(hide_non_directional);
- }
+ });
+
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.h
index 77a5105af..a875ff91f 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Settings/CarlaSettingsDelegate.h
@@ -5,12 +5,10 @@
// For a copy, see .
#pragma once
-
+#include "CoreMinimal.h"
+#include "Engine/World.h"
#include "CarlaSettingsDelegate.generated.h"
-
-class UCarlaSettings;
-
/// Used to set settings for every actor that is spawned into the world.
UCLASS(BlueprintType)
class CARLA_API UCarlaSettingsDelegate : public UObject
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp
index 62d5c6fb9..fb77bac04 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaVehicleController.cpp
@@ -42,8 +42,9 @@ void ACarlaVehicleController::Possess(APawn *aPawn)
// Get custom player state.
CarlaPlayerState = Cast(PlayerState);
check(CarlaPlayerState != nullptr);
- // We can set bounds extent already as it's not going to change.
- CarlaPlayerState->BoundsExtent = GetPossessedVehicle()->GetVehicleBoundsExtent();
+ // We can set the bounding box already as it's not going to change.
+ CarlaPlayerState->BoundingBoxTransform = GetPossessedVehicle()->GetVehicleBoundingBoxTransform();
+ CarlaPlayerState->BoundingBoxExtent = GetPossessedVehicle()->GetVehicleBoundingBoxExtent();
// Set HUD input.
CarlaHUD = Cast(GetHUD());
if (CarlaHUD != nullptr) {
@@ -114,9 +115,11 @@ void ACarlaVehicleController::IntersectPlayerWithRoadMap()
check(IsPossessingAVehicle());
auto Vehicle = GetPossessedVehicle();
constexpr float ChecksPerCentimeter = 0.1f;
+ const auto *BoundingBox = Vehicle->GetVehicleBoundingBox();
+ check(BoundingBox != nullptr);
auto Result = RoadMap->Intersect(
- Vehicle->GetVehicleTransform(),
- Vehicle->GetVehicleBoundsExtent(),
+ BoundingBox->GetComponentTransform(),
+ Vehicle->GetVehicleBoundingBoxExtent(), // Get scaled bounding box extent.
ChecksPerCentimeter);
CarlaPlayerState->OffRoadIntersectionFactor = Result.OffRoad;
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp
index 44ba18aaa..04e615b87 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.cpp
@@ -8,7 +8,6 @@
#include "CarlaWheeledVehicle.h"
#include "Agent/VehicleAgentComponent.h"
-#include "Vehicle/VehicleControl.h"
#include "Components/BoxComponent.h"
#include "Engine/CollisionProfile.h"
@@ -37,13 +36,6 @@ ACarlaWheeledVehicle::~ACarlaWheeledVehicle() {}
// -- Get functions ------------------------------------------------------------
// =============================================================================
-FTransform ACarlaWheeledVehicle::GetVehicleTransform() const
-{
- FTransform Transform = VehicleBounds->GetComponentTransform();
- Transform.SetScale3D(GetActorTransform().GetScale3D());
- return Transform;
-}
-
float ACarlaWheeledVehicle::GetVehicleForwardSpeed() const
{
return GetVehicleMovementComponent()->GetForwardSpeed();
@@ -59,7 +51,12 @@ int32 ACarlaWheeledVehicle::GetVehicleCurrentGear() const
return GetVehicleMovementComponent()->GetCurrentGear();
}
-FVector ACarlaWheeledVehicle::GetVehicleBoundsExtent() const
+FTransform ACarlaWheeledVehicle::GetVehicleBoundingBoxTransform() const
+{
+ return VehicleBounds->GetRelativeTransform();
+}
+
+FVector ACarlaWheeledVehicle::GetVehicleBoundingBoxExtent() const
{
return VehicleBounds->GetScaledBoxExtent();
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h
index bba09afba..b1c030a36 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/CarlaWheeledVehicle.h
@@ -9,6 +9,7 @@
#include "WheeledVehicle.h"
#include "Vehicle/CarlaWheeledVehicleState.h"
+#include "Vehicle/VehicleControl.h"
#include "CoreMinimal.h"
@@ -16,7 +17,6 @@
class UBoxComponent;
class UVehicleAgentComponent;
-struct FVehicleControl;
/// Base class for CARLA wheeled vehicles.
UCLASS()
@@ -44,7 +44,10 @@ public:
/// Transform of the vehicle. Location is shifted so it matches center of the
/// vehicle bounds rather than the actor's location.
UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
- FTransform GetVehicleTransform() const;
+ FTransform GetVehicleTransform() const
+ {
+ return GetActorTransform();
+ }
/// Forward speed in cm/s. Might be negative if goes backwards.
UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
@@ -58,9 +61,20 @@ public:
UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
int32 GetVehicleCurrentGear() const;
- /// Extent of the vehicle's bounds.
+ /// Transform of the vehicle's bounding box relative to the vehicle.
UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
- FVector GetVehicleBoundsExtent() const;
+ FTransform GetVehicleBoundingBoxTransform() const;
+
+ /// Extent of the vehicle's bounding box.
+ UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
+ FVector GetVehicleBoundingBoxExtent() const;
+
+ /// Get vehicle's bounding box component.
+ UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
+ UBoxComponent *GetVehicleBoundingBox() const
+ {
+ return VehicleBounds;
+ }
/// Get the maximum angle at which the front wheel can steer.
UFUNCTION(Category = "CARLA Wheeled Vehicle", BlueprintCallable)
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.cpp
index 17bc78da4..5dfe8a1f2 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.cpp
@@ -11,10 +11,12 @@
#include "Vehicle/CarlaWheeledVehicle.h"
#include "Vehicle/WheeledVehicleAIController.h"
-#include "Engine/PlayerStartPIE.h"
+
#include "EngineUtils.h"
#include "GameFramework/Character.h"
#include "GameFramework/PlayerStart.h"
+#include "TimerManager.h"
+#include "Kismet/GameplayStatics.h"
// =============================================================================
// -- Static local methods -----------------------------------------------------
@@ -35,8 +37,7 @@ static AWheeledVehicleAIController *GetController(ACarlaWheeledVehicle *Vehicle)
// =============================================================================
// Sets default values
-AVehicleSpawnerBase::AVehicleSpawnerBase(const FObjectInitializer& ObjectInitializer)
- : Super(ObjectInitializer)
+AVehicleSpawnerBase::AVehicleSpawnerBase(const FObjectInitializer& ObjectInitializer): Super(ObjectInitializer)
{
PrimaryActorTick.bCanEverTick = false;
}
@@ -55,31 +56,71 @@ void AVehicleSpawnerBase::BeginPlay()
SpawnPoints.Add(*It);
}
- UE_LOG(LogCarla, Log, TEXT("Found %d positions for spawning vehicles"), SpawnPoints.Num());
+ UE_LOG(LogCarla, Log, TEXT("Found %d PlayerStart positions for spawning vehicles"), SpawnPoints.Num());
- if (SpawnPoints.Num() < NumberOfVehicles) {
- bSpawnVehicles = false;
- UE_LOG(LogCarla, Error, TEXT("We don't have enough spawn points for vehicles!"));
+ if (SpawnPoints.Num() < NumberOfVehicles && SpawnPoints.Num()>0)
+ {
+ UE_LOG(LogCarla, Warning, TEXT("We don't have enough spawn points (PlayerStart) for vehicles!"));
+ if(SpawnPoints.Num()==0)
+ {
+ UE_LOG(LogCarla, Error, TEXT("At least one spawn point (PlayerStart) is needed to spawn vehicles!"));
+ } else
+ {
+ UE_LOG(LogCarla, Log,
+ TEXT("To cover the %d vehicles to spawn after beginplay, it will spawn one new vehicle each %f seconds"),
+ NumberOfVehicles - SpawnPoints.Num(),
+ TimeBetweenSpawnAttemptsAfterBegin
+ )
+;
+ }
}
+
+ if(NumberOfVehicles==0||SpawnPoints.Num()==0) bSpawnVehicles = false;
- if (bSpawnVehicles) {
- const int32 MaximumNumberOfAttempts = 4 * NumberOfVehicles;
+ if (bSpawnVehicles)
+ {
+ GetRandomEngine()->Shuffle(SpawnPoints);
+ const int32 MaximumNumberOfAttempts = SpawnPoints.Num();
int32 NumberOfAttempts = 0;
- while ((NumberOfVehicles > Vehicles.Num()) && (NumberOfAttempts < MaximumNumberOfAttempts)) {
- // Try to spawn one vehicle.
- TryToSpawnRandomVehicle();
+
+ while ((NumberOfVehicles > Vehicles.Num()) && (NumberOfAttempts < MaximumNumberOfAttempts))
+ {
+ SpawnVehicleAtSpawnPoint(*SpawnPoints[NumberOfAttempts]);
++NumberOfAttempts;
}
-
- if (NumberOfVehicles > Vehicles.Num()) {
+
+ if (NumberOfAttempts > NumberOfVehicles)
+ {
UE_LOG(LogCarla, Error, TEXT("Requested %d vehicles, but we were only able to spawn %d"), NumberOfVehicles, Vehicles.Num());
+ } else
+ {
+ if(NumberOfAttempts == NumberOfVehicles)
+ {
+ UE_LOG(LogCarla, Log, TEXT("Spawned all %d vehicles"), NumberOfAttempts);
+ } else
+ {
+ UE_LOG(LogCarla, Log,
+ TEXT("Starting the timer to spawn the other %d vehicles, one per %f seconds"),
+ NumberOfVehicles - NumberOfAttempts,
+ TimeBetweenSpawnAttemptsAfterBegin
+ );
+ GetWorld()->GetTimerManager().SetTimer(AttemptTimerHandle,this, &AVehicleSpawnerBase::SpawnVehicleAttempt, TimeBetweenSpawnAttemptsAfterBegin,false,-1);
+
+ }
+
}
}
}
+void AVehicleSpawnerBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
+{
+ GetWorld()->GetTimerManager().ClearAllTimersForObject(this);
+}
+
void AVehicleSpawnerBase::SetNumberOfVehicles(const int32 Count)
{
- if (Count > 0) {
+ if (Count > 0)
+ {
bSpawnVehicles = true;
NumberOfVehicles = Count;
} else {
@@ -90,7 +131,8 @@ void AVehicleSpawnerBase::SetNumberOfVehicles(const int32 Count)
void AVehicleSpawnerBase::TryToSpawnRandomVehicle()
{
auto SpawnPoint = GetRandomSpawnPoint();
- if (SpawnPoint != nullptr) {
+ if (SpawnPoint != nullptr)
+ {
SpawnVehicleAtSpawnPoint(*SpawnPoint);
} else {
UE_LOG(LogCarla, Error, TEXT("Unable to find spawn point"));
@@ -102,11 +144,13 @@ void AVehicleSpawnerBase::SpawnVehicleAtSpawnPoint(
{
ACarlaWheeledVehicle *Vehicle;
SpawnVehicle(SpawnPoint.GetActorTransform(), Vehicle);
- if ((Vehicle != nullptr) && !Vehicle->IsPendingKill()) {
+ if ((Vehicle != nullptr) && !Vehicle->IsPendingKill())
+ {
Vehicle->AIControllerClass = AWheeledVehicleAIController::StaticClass();
Vehicle->SpawnDefaultController();
auto Controller = GetController(Vehicle);
- if (Controller != nullptr) { // Sometimes fails...
+ if (Controller != nullptr)
+ { // Sometimes fails...
Controller->GetRandomEngine()->Seed(GetRandomEngine()->GenerateSeed());
Controller->SetRoadMap(GetRoadMap());
Controller->SetAutopilot(true);
@@ -118,6 +162,38 @@ void AVehicleSpawnerBase::SpawnVehicleAtSpawnPoint(
}
}
+void AVehicleSpawnerBase::SpawnVehicleAttempt()
+{
+ if(Vehicles.Num()>=NumberOfVehicles)
+ {
+ UE_LOG(LogCarla, Log, TEXT("All vehicles spawned correctly"));
+ return;
+ }
+
+ APlayerStart* spawnpoint = GetRandomSpawnPoint();
+ APawn* playerpawn = UGameplayStatics::GetPlayerPawn(GetWorld(),0);
+ const float DistanceToPlayer = playerpawn&&spawnpoint? FVector::Distance(playerpawn->GetActorLocation(),spawnpoint->GetActorLocation()):0.0f;
+ float NextTime = TimeBetweenSpawnAttemptsAfterBegin;
+ if(DistanceToPlayer>DistanceToPlayerBetweenSpawnAttemptsAfterBegin)
+ {
+ SpawnVehicleAtSpawnPoint(*spawnpoint);
+ } else
+ {
+ NextTime /= 2.0f;
+ }
+
+ if(Vehicles.Num()GetTimerManager();
+ if(AttemptTimerHandle.IsValid()) timemanager.ClearTimer(AttemptTimerHandle);
+ timemanager.SetTimer(AttemptTimerHandle,this, &AVehicleSpawnerBase::SpawnVehicleAttempt,NextTime,false,-1);
+ } else
+ {
+ UE_LOG(LogCarla, Log, TEXT("Last vehicle spawned correctly"));
+ }
+
+}
+
APlayerStart *AVehicleSpawnerBase::GetRandomSpawnPoint()
{
return (SpawnPoints.Num() > 0 ? GetRandomEngine()->PickOne(SpawnPoints) : nullptr);
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.h
index c079c53a6..dcca93168 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/VehicleSpawnerBase.h
@@ -28,6 +28,9 @@ protected:
// Called when the game starts or when spawned
virtual void BeginPlay() override;
+ // Called when the actor is removed from the level
+ virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
+
UFUNCTION(BlueprintImplementableEvent)
void SpawnVehicle(const FTransform &SpawnTransform, ACarlaWheeledVehicle *&SpawnedCharacter);
@@ -57,6 +60,9 @@ public:
{
return RoadMap;
}
+ /** Function called to spawn another vehicle when there is not enough spawn points in the beginplay */
+ UFUNCTION(Category = "Vehicle Spawner", BlueprintCallable)
+ void SpawnVehicleAttempt();
protected:
@@ -65,7 +71,7 @@ protected:
void SpawnVehicleAtSpawnPoint(const APlayerStart &SpawnPoint);
UPROPERTY()
- URoadMap *RoadMap;
+ URoadMap *RoadMap = nullptr;
/** If false, no walker will be spawned. */
UPROPERTY(Category = "Vehicle Spawner", EditAnywhere)
@@ -75,9 +81,22 @@ protected:
UPROPERTY(Category = "Vehicle Spawner", EditAnywhere, meta = (EditCondition = bSpawnVehicles, ClampMin = "1"))
int32 NumberOfVehicles = 10;
- UPROPERTY(Category = "Vechicle Spawner", VisibleAnywhere, AdvancedDisplay)
+ UPROPERTY(Category = "Vehicle Spawner", VisibleAnywhere, AdvancedDisplay)
TArray SpawnPoints;
UPROPERTY(Category = "Vehicle Spawner", BlueprintReadOnly, VisibleAnywhere, AdvancedDisplay)
TArray Vehicles;
+
+ /** Time to spawn new vehicles after begin play if there was not enough spawn points at the moment */
+ UPROPERTY(Category = "Vehicle Spawner", BlueprintReadWrite, EditAnywhere, meta = (ClampMin = "0.1", ClampMax = "1000.0", UIMin = "0.1", UIMax = "1000.0"))
+ float TimeBetweenSpawnAttemptsAfterBegin = 3.0f;
+
+ /** Min Distance to the player vehicle to validate a spawn point location for the next vehicle spawn attempt */
+ UPROPERTY(Category = "Vehicle Spawner", BlueprintReadWrite, EditAnywhere, meta = (ClampMin = "10", ClampMax = "10000", UIMin = "10", UIMax = "10000"))
+ float DistanceToPlayerBetweenSpawnAttemptsAfterBegin = 5000;
+private:
+
+ /** Time handler to spawn more vehicles in the case we could not do it in the beginplay */
+ FTimerHandle AttemptTimerHandle;
+
};
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp
index 295b16960..008e6388a 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Vehicle/WheeledVehicleAIController.cpp
@@ -40,7 +40,7 @@ static bool IsThereAnObstacleAhead(
const FVector &Direction)
{
const auto ForwardVector = Vehicle.GetVehicleOrientation();
- const auto VehicleBounds = Vehicle.GetVehicleBoundsExtent();
+ const auto VehicleBounds = Vehicle.GetVehicleBoundingBoxExtent();
const float Distance = std::max(50.0f, Speed * Speed); // why?
@@ -250,7 +250,7 @@ float AWheeledVehicleAIController::GoToNextTargetLocation(FVector &Direction)
float AWheeledVehicleAIController::CalcStreeringValue(FVector &direction)
{
float steering = 0;
- FVector BoxExtent = Vehicle->GetVehicleBoundsExtent();
+ FVector BoxExtent = Vehicle->GetVehicleBoundingBoxExtent();
FVector forward = Vehicle->GetActorForwardVector();
FVector rightSensorPosition(BoxExtent.X / 2.0f, (BoxExtent.Y / 2.0f) + 100.0f, 0.0f);
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp
index 488b6bf90..31f8aa246 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.cpp
@@ -10,7 +10,6 @@
#include "Navigation/CrowdFollowingComponent.h"
#include "Perception/AIPerceptionComponent.h"
#include "Perception/AISenseConfig_Sight.h"
-#include "Perception/AISense_Sight.h"
#include "WheeledVehicle.h"
#include "WheeledVehicleMovementComponent.h"
@@ -27,8 +26,8 @@ static constexpr float UPDATE_TIME_IN_SECONDS = 0.6f;
static constexpr float PREVISION_TIME_IN_SECONDS = 5.0f;
static constexpr float WALKER_SIGHT_RADIUS = 500.0f;
static constexpr float WALKER_SPEED_DAMPING = 4.0f;
-static constexpr float WALKER_PERIPHERAL_VISION_ANGLE_IN_DEGREES = 155.0f;
-static constexpr float WALKER_MAX_TIME_PAUSED = 10.0f;
+static constexpr float WALKER_PERIPHERAL_VISION_ANGLE_IN_DEGREES = 130.0f;
+static constexpr float WALKER_MAX_TIME_PAUSED = 5.0f;
static constexpr float VEHICLE_SAFETY_RADIUS = 600.0f;
@@ -176,11 +175,13 @@ void AWalkerAIController::Tick(float DeltaSeconds)
{
Super::Tick(DeltaSeconds);
TimeInState+=DeltaSeconds;
- if (Status != EWalkerStatus::RunOver) {
+ if (Status != EWalkerStatus::RunOver)
+ {
switch (GetMoveStatus())
{
- case EPathFollowingStatus::Idle:
- case EPathFollowingStatus::Waiting:
+ default: break;
+ case EPathFollowingStatus::Idle:
+ //case EPathFollowingStatus::Waiting: //<-- incomplete path
LOG_AI_WALKER(Warning, "is stuck!");
ChangeStatus(EWalkerStatus::Stuck);
break;
@@ -190,7 +191,8 @@ void AWalkerAIController::Tick(float DeltaSeconds)
TryResumeMovement();
}
break;
- };
+
+ };
}
}
@@ -225,7 +227,7 @@ void AWalkerAIController::OnMoveCompleted(
ChangeStatus(EWalkerStatus::MoveCompleted);
}
-void AWalkerAIController::SenseActors(const TArray Actors)
+void AWalkerAIController::SenseActors(TArray Actors)
{
const auto *aPawn = GetPawn();
if ((Status == EWalkerStatus::Moving) &&
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h
index cc218d1f7..986d22fde 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerAIController.h
@@ -54,6 +54,9 @@ public:
UFUNCTION(BlueprintCallable)
void TrySetMovement(bool paused);
+ UFUNCTION(BlueprintCallable)
+ float GetTimeInState() const { return TimeInState; }
+
private:
void ChangeStatus(EWalkerStatus status);
void TryResumeMovement();
@@ -68,6 +71,6 @@ private:
UPROPERTY(VisibleAnywhere)
EWalkerStatus Status = EWalkerStatus::Unknown;
-
+ /** Continous time in the same EWalkerStatus */
float TimeInState=0.0f;
};
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.cpp
index 585315052..f9113fc22 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.cpp
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.cpp
@@ -10,10 +10,10 @@
#include "Util/RandomEngine.h"
#include "Walker/WalkerAIController.h"
#include "Walker/WalkerSpawnPoint.h"
-
#include "Components/BoxComponent.h"
#include "EngineUtils.h"
#include "GameFramework/Character.h"
+#include "Kismet/KismetSystemLibrary.h"
// =============================================================================
// -- Static local methods -----------------------------------------------------
@@ -78,14 +78,19 @@ void AWalkerSpawnerBase::BeginPlay()
SpawnPoints.Add(SpawnPoint);
}
}
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
UE_LOG(LogCarla, Log, TEXT("Found %d positions for spawning walkers at begin play."), BeginSpawnPoints.Num());
UE_LOG(LogCarla, Log, TEXT("Found %d positions for spawning walkers during game play."), SpawnPoints.Num());
-
+ #endif
if (SpawnPoints.Num() < 2) {
bSpawnWalkers = false;
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
UE_LOG(LogCarla, Error, TEXT("We don't have enough spawn points for walkers!"));
+ #endif
} else if (BeginSpawnPoints.Num() < NumberOfWalkers) {
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
UE_LOG(LogCarla, Warning, TEXT("Requested %d walkers, but we only have %d spawn points. Some will fail to spawn."), NumberOfWalkers, BeginSpawnPoints.Num());
+ #endif
}
GetRandomEngine()->Shuffle(BeginSpawnPoints);
@@ -97,7 +102,9 @@ void AWalkerSpawnerBase::BeginPlay()
++Count;
}
}
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
UE_LOG(LogCarla, Log, TEXT("Spawned %d walkers at begin play."), Count);
+ #endif
}
}
@@ -110,45 +117,139 @@ void AWalkerSpawnerBase::Tick(float DeltaTime)
TryToSpawnWalkerAt(GetRandomSpawnPoint());
}
- if (WalkersBlackList.Num() > 0) {
- // If still stuck in the black list, just kill it.
- const int32 Index = (++CurrentIndexToCheck % WalkersBlackList.Num());
- auto Walker = WalkersBlackList[Index];
- const auto Status = GetWalkerStatus(Walker);
- if ((Status == EWalkerStatus::MoveCompleted) ||
- (Status == EWalkerStatus::Invalid) ||
- (Status == EWalkerStatus::RunOver)) {
- WalkersBlackList.RemoveAtSwap(Index);
- if ((Walker != nullptr) && (Status != EWalkerStatus::RunOver)) {
- Walker->Destroy();
+ if (WalkersBlackList.Num() > 0)
+ {
+ CurrentBlackWalkerIndexToCheck = ++CurrentBlackWalkerIndexToCheck % WalkersBlackList.Num();
+ ACharacter* BlackListedWalker = WalkersBlackList[CurrentBlackWalkerIndexToCheck];
+ AWalkerAIController* controller = BlackListedWalker!=nullptr?Cast(BlackListedWalker->GetController()):nullptr;
+ if(BlackListedWalker != nullptr && controller!=nullptr && IsValid(BlackListedWalker))
+ {
+ const auto Status = GetWalkerStatus(BlackListedWalker);
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
+ UE_LOG(LogCarla, Log, TEXT("Watching walker %s with state %d"), *UKismetSystemLibrary::GetDisplayName(BlackListedWalker), (int)Status);
+ #endif
+ switch(Status)
+ {
+ case EWalkerStatus::RunOver:{
+ //remove from list and wait for auto-destroy
+ WalkersBlackList.RemoveAtSwap(CurrentBlackWalkerIndexToCheck);
+ break;
+ }
+ case EWalkerStatus::MoveCompleted:
+ {
+ BlackListedWalker->Destroy();
+ break;
+ }
+ default: {
+ switch(controller->GetMoveStatus())
+ {
+ case EPathFollowingStatus::Idle:
+ if(!TrySetDestination(*BlackListedWalker))
+ {
+ if(!SetRandomWalkerDestination(BlackListedWalker))
+ {
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
+ UE_LOG(LogCarla,Error,TEXT("Could not set a random destination to walker %s"),*UKismetSystemLibrary::GetDisplayName(BlackListedWalker));
+ #endif
+ }
+ }
+ break;
+ case EPathFollowingStatus::Waiting:
+ //incomplete path
+ break;
+ case EPathFollowingStatus::Paused:
+ //waiting for blueprint code
+ break;
+ case EPathFollowingStatus::Moving:
+ if(BlackListedWalker->GetVelocity().Size()>1.0f)
+ {
+ WalkersBlackList.RemoveAtSwap(CurrentBlackWalkerIndexToCheck);
+ Walkers.Add(BlackListedWalker);
+ }
+ break;
+ default: break;
+ }
+ break;
+ }
}
- }
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
+ UE_LOG(LogCarla, Log, TEXT("New state for walker %s : %d"), *UKismetSystemLibrary::GetDisplayName(BlackListedWalker), (int)GetWalkerStatus(BlackListedWalker));
+ #endif
+ }
+
}
- if (Walkers.Num() > 0) {
+ if (Walkers.Num() > 0)
+ {
// Check one walker, if fails black-list it or kill it.
- const int32 Index = (++CurrentIndexToCheck % Walkers.Num());
- auto Walker = Walkers[Index];
- const auto Status = GetWalkerStatus(Walker);
-
- if ((Status == EWalkerStatus::MoveCompleted) ||
- (Status == EWalkerStatus::Invalid) ||
- (Status == EWalkerStatus::RunOver)) {
- // Kill it.
- Walkers.RemoveAtSwap(Index);
- // If it was run over will self-destroy.
- if ((Walker != nullptr) && (Status != EWalkerStatus::RunOver)) {
- Walker->Destroy();
- }
- } else if (Status == EWalkerStatus::Stuck) {
- // Black-list it.
- TrySetDestination(*Walker);
- WalkersBlackList.Add(Walker);
- Walkers.RemoveAtSwap(Index);
+ CurrentWalkerIndexToCheck = ++CurrentWalkerIndexToCheck % Walkers.Num();
+ auto Walker = Walkers[CurrentWalkerIndexToCheck];
+ if(Walker == nullptr || !IsValid(Walker))
+ {
+ Walkers.RemoveAtSwap(CurrentWalkerIndexToCheck);
+ } else {
+ const auto Status = GetWalkerStatus(Walker);
+ switch (Status)
+ {
+ default:
+ case EWalkerStatus::Paused:
+ case EWalkerStatus::Unknown:
+ break;
+ case EWalkerStatus::RunOver: {
+ Walkers.RemoveAtSwap(CurrentWalkerIndexToCheck);
+ break;
+ }
+ case EWalkerStatus::MoveCompleted:
+ Walker->Destroy();
+ break;
+ case EWalkerStatus::Invalid:
+ case EWalkerStatus::Stuck:
+ {
+ SetRandomWalkerDestination(Walker);
+ // Black-list it and wait for this walker to move
+ WalkersBlackList.Add(Walker);
+ Walkers.RemoveAtSwap(CurrentWalkerIndexToCheck);
+ break;
+ }
+ }
}
}
}
+bool AWalkerSpawnerBase::SetRandomWalkerDestination(ACharacter *Walker)
+{
+ const auto &DestinationPoint = GetRandomSpawnPoint();
+ auto Controller = GetController(Walker);
+ if(!Controller) {
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
+ UE_LOG(LogCarla, Warning, TEXT("AWalkerSpawnerBase::SetRandomWalkerDestination: Walker %s has no controller"),
+ *UKismetSystemLibrary::GetDisplayName(Walker)
+ );
+ #endif
+ return false;
+ }
+ const EPathFollowingRequestResult::Type request_result = Controller->MoveToLocation(DestinationPoint.GetActorLocation(),-1.0f,false,true,true,true,nullptr,true);
+ switch(request_result)
+ {
+ case EPathFollowingRequestResult::Type::Failed:
+ {
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
+ UE_LOG(LogCarla, Warning, TEXT("AWalkerSpawnerBase::SetRandomWalkerDestination: Bad destination point %s"),
+ *UKismetSystemLibrary::GetDisplayName(&DestinationPoint)
+ );
+ #endif
+ return false;
+ }
+ case EPathFollowingRequestResult::Type::AlreadyAtGoal:{
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
+ UE_LOG(LogCarla, Log, TEXT("AWalkerSpawnerBase::SetRandomWalkerDestination already in destination, generating new location"));
+ #endif
+ return SetRandomWalkerDestination(Walker);
+ }
+ default: case EPathFollowingRequestResult::Type::RequestSuccessful: return true;
+ }
+}
+
// =============================================================================
// -- Other member functions ---------------------------------------------------
// =============================================================================
@@ -205,7 +306,10 @@ bool AWalkerSpawnerBase::TryToSpawnWalkerAt(const AWalkerSpawnPointBase &SpawnPo
// Add walker and set destination.
Walkers.Add(Walker);
- Controller->MoveToLocation(Destination);
+ if (Controller->MoveToLocation(Destination,-1.0f,false,true,true,true,nullptr,true)!=EPathFollowingRequestResult::Type::RequestSuccessful)
+ {
+ SetRandomWalkerDestination(Walker);
+ }
return true;
}
@@ -214,15 +318,22 @@ bool AWalkerSpawnerBase::TrySetDestination(ACharacter &Walker)
// Try to retrieve controller.
auto Controller = GetController(&Walker);
if (Controller == nullptr) {
+ UE_LOG(LogCarla, Warning, TEXT("Could not get valid controller for walker: %s"), *Walker.GetName());
return false;
}
// Try find destination.
FVector Destination;
if (!TryGetValidDestination(Walker.GetActorLocation(), Destination)) {
+ #ifdef CARLA_AI_WALKERS_EXTRA_LOG
+ UE_LOG(
+ LogCarla, Warning,
+ TEXT("Could not get a new destiny: %s for walker: %s"),
+ *Destination.ToString(), *Walker.GetName()
+ );
+ #endif
return false;
}
- Controller->MoveToLocation(Destination);
- return true;
+ return Controller->MoveToLocation(Destination,-1.0f,false,true,true,true,nullptr,true)==EPathFollowingRequestResult::RequestSuccessful;
}
diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.h
index ba17fae52..c1d05d5dc 100644
--- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.h
+++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Walker/WalkerSpawnerBase.h
@@ -45,6 +45,7 @@ public:
virtual void Tick(float DeltaTime) override;
+
/// @}
// ===========================================================================
/// @name Blueprintable functions
@@ -87,6 +88,7 @@ private:
bool TrySetDestination(ACharacter &Walker);
+ bool SetRandomWalkerDestination(ACharacter * Walker);
/// @}
private:
@@ -116,5 +118,7 @@ private:
UPROPERTY(Category = "Walker Spawner", VisibleAnywhere, AdvancedDisplay)
TArray WalkersBlackList;
- uint32 CurrentIndexToCheck = 0u;
+ uint32 CurrentWalkerIndexToCheck = 0u;
+
+ uint32 CurrentBlackWalkerIndexToCheck = 0u;
};
diff --git a/Util/CarlaServer/include/carla/carla_server.h b/Util/CarlaServer/include/carla/carla_server.h
index 813d04c7d..d9a735480 100644
--- a/Util/CarlaServer/include/carla/carla_server.h
+++ b/Util/CarlaServer/include/carla/carla_server.h
@@ -43,6 +43,11 @@ extern "C" {
struct carla_rotation3d rotation;
};
+ struct carla_bounding_box {
+ struct carla_transform transform;
+ struct carla_vector3d extent;
+ };
+
/* ======================================================================== */
/* -- agents -------------------------------------------------------------- */
/* ======================================================================== */
@@ -66,7 +71,7 @@ extern "C" {
uint32_t id;
uint32_t type;
struct carla_transform transform;
- struct carla_vector3d box_extent;
+ struct carla_bounding_box bounding_box;
float forward_speed;
};
@@ -159,8 +164,8 @@ extern "C" {
struct carla_player_measurements {
/** World transform of the player. */
struct carla_transform transform;
- /** Extent of the bounding box of the player. */
- struct carla_vector3d box_extent;
+ /** Bounding box of the player. */
+ struct carla_bounding_box bounding_box;
/** Current acceleration of the player. */
struct carla_vector3d acceleration;
/** Forward speed in m/s. */
@@ -184,6 +189,8 @@ extern "C" {
/* ======================================================================== */
struct carla_measurements {
+ /** Frame counter. */
+ uint32_t frame_number;
/** Time-stamp of the current frame, in milliseconds as given by the OS. */
uint32_t platform_timestamp;
/** In-game time-stamp, milliseconds elapsed since the beginning of the current level. */
diff --git a/Util/CarlaServer/source/carla/server/CarlaEncoder.cpp b/Util/CarlaServer/source/carla/server/CarlaEncoder.cpp
index 7eea0f40f..129863628 100644
--- a/Util/CarlaServer/source/carla/server/CarlaEncoder.cpp
+++ b/Util/CarlaServer/source/carla/server/CarlaEncoder.cpp
@@ -54,6 +54,12 @@ namespace server {
Set(lhs->mutable_rotation(), rhs.rotation);
}
+ static void Set(cs::BoundingBox *lhs, const carla_bounding_box &rhs) {
+ DEBUG_ASSERT(lhs != nullptr);
+ Set(lhs->mutable_transform(), rhs.transform);
+ Set(lhs->mutable_extent(), rhs.extent);
+ }
+
static void Set(cs::Sensor *lhs, const carla_sensor_definition &rhs) {
DEBUG_ASSERT(lhs != nullptr);
lhs->set_id(rhs.id);
@@ -79,14 +85,14 @@ namespace server {
static void SetVehicle(cs::Vehicle *lhs, const carla_agent &rhs) {
DEBUG_ASSERT(lhs != nullptr);
Set(lhs->mutable_transform(), rhs.transform);
- Set(lhs->mutable_box_extent(), rhs.box_extent);
+ Set(lhs->mutable_bounding_box(), rhs.bounding_box);
lhs->set_forward_speed(rhs.forward_speed);
}
static void SetPedestrian(cs::Pedestrian *lhs, const carla_agent &rhs) {
DEBUG_ASSERT(lhs != nullptr);
Set(lhs->mutable_transform(), rhs.transform);
- Set(lhs->mutable_box_extent(), rhs.box_extent);
+ Set(lhs->mutable_bounding_box(), rhs.bounding_box);
lhs->set_forward_speed(rhs.forward_speed);
}
@@ -149,13 +155,14 @@ namespace server {
std::string CarlaEncoder::Encode(const carla_measurements &values) {
static thread_local auto *message = _protobuf.CreateMessage();
DEBUG_ASSERT(message != nullptr);
+ message->set_frame_number(values.frame_number);
message->set_platform_timestamp(values.platform_timestamp);
message->set_game_timestamp(values.game_timestamp);
// Player measurements.
auto *player = message->mutable_player_measurements();
DEBUG_ASSERT(player != nullptr);
Set(player->mutable_transform(), values.player_measurements.transform);
- Set(player->mutable_box_extent(), values.player_measurements.box_extent);
+ Set(player->mutable_bounding_box(), values.player_measurements.bounding_box);
Set(player->mutable_acceleration(), values.player_measurements.acceleration);
player->set_forward_speed(values.player_measurements.forward_speed);
player->set_collision_vehicles(values.player_measurements.collision_vehicles);
diff --git a/Util/CarlaServer/source/test/Sensor.cpp b/Util/CarlaServer/source/test/Sensor.cpp
index 8bb12e6a7..bac806a24 100644
--- a/Util/CarlaServer/source/test/Sensor.cpp
+++ b/Util/CarlaServer/source/test/Sensor.cpp
@@ -17,11 +17,12 @@ namespace test {
std::lock_guard lock(_mutex);
const struct {
+ uint64_t FrameNumber;
uint32_t Width;
uint32_t Height;
uint32_t Type;
float FOV;
- } ImageHeader = {300u, 200u, 1u, 90.0f};
+ } ImageHeader = {++_frame_number, 300u, 200u, 1u, 90.0f};
_data.header_size = sizeof(ImageHeader);
auto header = std::make_unique(_data.header_size);
diff --git a/Util/CarlaServer/source/test/Sensor.h b/Util/CarlaServer/source/test/Sensor.h
index 745cc1587..10b364fd1 100644
--- a/Util/CarlaServer/source/test/Sensor.h
+++ b/Util/CarlaServer/source/test/Sensor.h
@@ -34,6 +34,8 @@ namespace test {
Sensor(uint32_t id);
+ uint64_t _frame_number = 0u;
+
mutable std::mutex _mutex;
const std::string _name;
diff --git a/Util/CarlaServer/source/test/Test_CarlaServer.cpp b/Util/CarlaServer/source/test/Test_CarlaServer.cpp
index 183e7a111..01a32d1ea 100644
--- a/Util/CarlaServer/source/test/Test_CarlaServer.cpp
+++ b/Util/CarlaServer/source/test/Test_CarlaServer.cpp
@@ -106,7 +106,7 @@ TEST(CarlaServerAPI, SimBlocking) {
agents_data[i].id = i;
agents_data[i].type = CARLA_SERVER_AGENT_VEHICLE;
agents_data[i].transform = start_locations[0u];
- agents_data[i].box_extent = {100.0f, 100.0f, 100.0f};
+ agents_data[i].bounding_box = {start_locations[0u], {100.0f, 100.0f, 100.0f}};
agents_data[i].forward_speed = 50.0f;
}
diff --git a/Util/ContentVersions.txt b/Util/ContentVersions.txt
index 0670a9818..b664fd7e6 100644
--- a/Util/ContentVersions.txt
+++ b/Util/ContentVersions.txt
@@ -10,3 +10,4 @@
0.7.1: 1gf3YaFIjwr1EaK6qxq2V-a510Brt9Imq
0.8.0: 1tA-WwKA0RNhBoENYunqF3-F_wg11dL86
0.8.1: 1su5wQH7KJphAcirMA8VEDLndGigQ9tzq
+Latest: 17Fi8DYdNkBJ5AIsh_uUbUPdD-XeVlTf9
diff --git a/Util/Proto/carla_server.proto b/Util/Proto/carla_server.proto
index 4c71f5300..9a0ea9110 100644
--- a/Util/Proto/carla_server.proto
+++ b/Util/Proto/carla_server.proto
@@ -32,6 +32,11 @@ message Transform {
Rotation3D rotation = 3;
}
+message BoundingBox {
+ Transform transform = 1;
+ Vector3D extent = 2;
+}
+
// =============================================================================
// -- Sensors ------------------------------------------------------------------
// =============================================================================
@@ -54,13 +59,13 @@ message Sensor {
message Vehicle {
Transform transform = 1;
- Vector3D box_extent = 2;
+ BoundingBox bounding_box = 4;
float forward_speed = 3;
}
message Pedestrian {
Transform transform = 1;
- Vector3D box_extent = 2;
+ BoundingBox bounding_box = 4;
float forward_speed = 3;
}
@@ -126,7 +131,7 @@ message Measurements {
message PlayerMeasurements {
Transform transform = 1;
- Vector3D box_extent = 11;
+ BoundingBox bounding_box = 12;
Vector3D acceleration = 3;
float forward_speed = 4;
@@ -141,6 +146,8 @@ message Measurements {
Control autopilot_control = 10;
}
+ uint64 frame_number = 5;
+
uint32 platform_timestamp = 1;
uint32 game_timestamp = 2;