Merge master into manishthani/no_rendering_mode
This commit is contained in:
commit
9ab1411bd4
|
@ -1,7 +1,16 @@
|
|||
## Latest Changes
|
||||
* Fix parsing of OpenDrive geoReference exported by RoadRunner
|
||||
* Added recording/replaying functionality to manual_control.py script.
|
||||
- CTRL + R: Toggle recording (file is always 'manual_recording.rec')
|
||||
- CTRL + P: Replay last recording.
|
||||
- CTRL + -: Subtract 1 second the start time of the replayer.
|
||||
- CTRL + =: Add 1 second the start time of the replayer.
|
||||
- CTRL + SHIFT + -: Subtract 10 seconds the start time of the replayer.
|
||||
- CTRL + SHIFT + =: Add 10 seconds the start time of the replayer.
|
||||
- Note: A negative time start means to replay from the end of the recording (-2 = replay the last 2 seconds)
|
||||
* Added manual_control_steeringwheel.py to control agents using Logitech G29 steering wheels (and maybe others).
|
||||
* Fixed `manual_control.py` and `no_rendering_mode.py` to prevent crashes when used in "no rendering mode"
|
||||
* Added scripts and tool to import map direcly from .fbx and .xodr files into the system.
|
||||
* Added movable props present in the map (e.g. chairs and tables) as actors so they can be controlled from Python
|
||||
* Refactored `no_rendering_mode.py` to improve performance and interface
|
||||
* Fixed traffic light when it gets illuminated by the hero vehicle in `no_rendering_mode.py`
|
||||
|
|
|
@ -0,0 +1,70 @@
|
|||
<h1>Automatically generate a map from RoadRunner</h1>
|
||||
|
||||
!!! important
|
||||
The given scripts only works if the files are kept in the folders
|
||||
detailed below.
|
||||
|
||||
This script is aimed to reduce the time needed to setup a map inside Carla's project.
|
||||
Also, in combination of the [import / export scripts](export_import_dist.md) will allow
|
||||
the user to generate a simple map without opening Unreal Engine.
|
||||
|
||||
!!! important
|
||||
The script does heavy use of Unreal's capabilities, so it is needed to be installed
|
||||
and setup, as the import fbx action is done directly over the code project, not a
|
||||
distribution build.
|
||||
|
||||
|
||||
<h4>How to import a fbx</h4>
|
||||
The current script only work for files placed with the follow structure (RoadRunnerFiles is
|
||||
located in the root folder):
|
||||
|
||||
```sh
|
||||
RoadRunnerFiles/
|
||||
├── MapToImport01
|
||||
│ ├── Asphalt1_Diff.png
|
||||
│ ├── Asphalt1_Norm.png
|
||||
│ ├── Asphalt1_Spec.png
|
||||
│ ├── Grass1_Diff.png
|
||||
│ ├── Grass1_Norm.png
|
||||
│ ├── Grass1_Spec.png
|
||||
│ ├── LaneMarking1_Diff.png
|
||||
│ ├── LaneMarking1_Norm.png
|
||||
│ ├── LaneMarking1_Spec.png
|
||||
│ ├── MapToImport01.fbx
|
||||
│ └── MapToImport01.xodr
|
||||
└── MapToImport02
|
||||
├── Asphalt1_Diff.png
|
||||
├── Asphalt1_Norm.png
|
||||
├── Asphalt1_Spec.png
|
||||
├── Concrete1_Diff.png
|
||||
├── Concrete1_Norm.png
|
||||
├── Concrete1_Spec.png
|
||||
├── Grass1_Diff.png
|
||||
├── Grass1_Norm.png
|
||||
├── Grass1_Spec.png
|
||||
├── LaneMarking1_Diff.png
|
||||
├── LaneMarking1_Norm.png
|
||||
├── LaneMarking1_Spec.png
|
||||
├── MapToImport02.fbx
|
||||
└── MapToImport02.xodr
|
||||
```
|
||||
|
||||
Under RoadRunnerFiles, place each "Export" folder obtained from RoadRunner and
|
||||
rename it with the name of the map to be imported. It have to match the <b>.fbx</b>
|
||||
and <b>.xodr</b> files.
|
||||
|
||||
Now, simply go into the PythonAPI/util folder and run <b>generate_map.py</b>
|
||||
|
||||
!!! important
|
||||
The script, by default, checks the <i>/Unreal/CarlaUE4/Content/Carla/ExportedMaps</i> for matching names.
|
||||
If a map with the same name as a to-be-imported map is found, it will notify the user and won't do anything.
|
||||
To override this, <b>generate_map.py</b> can be invoked with the <b>--force</b> flag.
|
||||
|
||||
After the script finishes, all a map with the same name of the folder and files will be located under
|
||||
<i>/Unreal/CarlaUE4/Content/Carla/Maps</i> with all the static meshes and placed, textures, waypoints and routes
|
||||
generated.
|
||||
|
||||
!!! important
|
||||
There is a bug in RoadRunner that generates wrong materials automatically and they get broken inside Unreal.
|
||||
By adding the flag <b>--usecarlamats</b> the meshes will use the materials provided by Carla's project,
|
||||
that will also <b>react to the weather</b>.
|
Binary file not shown.
After Width: | Height: | Size: 1.8 MiB |
Binary file not shown.
After Width: | Height: | Size: 284 KiB |
Binary file not shown.
After Width: | Height: | Size: 348 KiB |
Binary file not shown.
After Width: | Height: | Size: 2.6 MiB |
|
@ -26,6 +26,7 @@
|
|||
* [Running in a Docker](carla_docker.md)
|
||||
* [How to make a new map with RoadRunner](how_to_make_a_new_map.md)
|
||||
* [How to link Epic's Automotive Materials](epic_automotive_materials.md)
|
||||
* [How to automatically generate a map from RoadRunner](generate_map_from_fbx.md)
|
||||
* [How to export and import maps to distribution builds](export_import_dist.md)
|
||||
|
||||
<h3>Contributing</h3>
|
||||
|
|
|
@ -12,6 +12,11 @@
|
|||
- `get_client_version()`
|
||||
- `get_server_version()`
|
||||
- `get_world()`
|
||||
- `start_recorder(string filename)`
|
||||
- `replay_file(string filename, float start, float duration, int camera_follow_id)`
|
||||
- `show_recorder_file_info(string filename)`
|
||||
- `show_recorder_collisions(string filename, char category1, char category2)`
|
||||
- `show_recorder_actors_blocked(string filename, float min_time, float min_distance)`
|
||||
|
||||
## `carla.World`
|
||||
|
||||
|
|
|
@ -410,3 +410,266 @@ for each road segment in the map.
|
|||
|
||||
Finally, to allow access to the whole road information, the map object can be
|
||||
converted to OpenDrive format, and saved to disk as such.
|
||||
|
||||
#### Recording and Replaying system
|
||||
|
||||
CARLA includes now a recording and replaying API, that allows to record a simulation in a file and later replay that simulation. The file is written on server side only, and it includes which **actors are created or destroyed** in the simulation, the **state of the traffic lights** and the **position/orientation** of all vehicles and walkers.
|
||||
|
||||
All data is written in a binary file on the server, on folder **CarlaUE4/Saved**. As estimation, a simulation with about 150 actors (50 traffic lights, 100 vehicles) for 1h of recording takes around 200 Mb in size.
|
||||
|
||||
To start recording we only need to supply a file name:
|
||||
|
||||
```py
|
||||
client.start_recorder("recording01.log")
|
||||
```
|
||||
|
||||
To stop the recording, we need to call:
|
||||
|
||||
```py
|
||||
client.stop_recorder()
|
||||
```
|
||||
|
||||
At any point we can replay a simulation, specifying the filename:
|
||||
|
||||
```py
|
||||
client.replay_file("recording01.log")
|
||||
```
|
||||
The replayer will create and destroy all actors that were recorded, and move all actors and setting the traffic lights as they were working at that moment.
|
||||
|
||||
When replaying we have some other options that we can use, the full API call is:
|
||||
|
||||
```py
|
||||
client.replay_file("recording01.log", start, duration, camera)
|
||||
```
|
||||
* **start**: time we want to start the simulation.
|
||||
* If the value is positive, it means the number of seconds from the beginning.
|
||||
Ex: a value of 10 will start the simulation at second 10.
|
||||
* If the value is negative, it means the number of seconds from the end.
|
||||
Ex: a value of -10 will replay only the last 10 seconds of the simulation.
|
||||
* **duration**: we can say how many seconds we want to play. If the simulation has not reached the end, then all actors will have autopilot enabled automatically. The intention here is to allow for replaying a piece of a simulation and then let all actors start driving in autopilot again.
|
||||
* **camera**: we can specify the Id of an actor and then the camera will follow that actor while replaying. Continue reading to know which Id has an actor.
|
||||
|
||||
We can know details about a recorded simulation, using this API:
|
||||
|
||||
```py
|
||||
client.show_recorder_file_info("recording01.log")
|
||||
```
|
||||
|
||||
The output result is something like this:
|
||||
|
||||
```
|
||||
Version: 1
|
||||
Map: Town05
|
||||
Date: 02/21/19 10:46:20
|
||||
|
||||
Frame 1 at 0 seconds
|
||||
Create 2190: spectator (0) at (-260, -200, 382.001)
|
||||
Create 2191: traffic.traffic_light (3) at (4255, 10020, 0)
|
||||
Create 2192: traffic.traffic_light (3) at (4025, 7860, 0)
|
||||
Create 2193: traffic.traffic_light (3) at (1860, 7975, 0)
|
||||
Create 2194: traffic.traffic_light (3) at (1915, 10170, 0)
|
||||
...
|
||||
Create 2258: traffic.speed_limit.90 (0) at (21651.7, -1347.59, 15)
|
||||
Create 2259: traffic.speed_limit.90 (0) at (5357, 21457.1, 15)
|
||||
Create 2260: traffic.speed_limit.90 (0) at (858, 18176.7, 15)
|
||||
Frame 2 at 0.0254253 seconds
|
||||
Create 2276: vehicle.mini.cooperst (1) at (4347.63, -8409.51, 120)
|
||||
number_of_wheels = 4
|
||||
object_type =
|
||||
color = 255,241,0
|
||||
role_name = autopilot
|
||||
Frame 4 at 0.0758538 seconds
|
||||
Create 2277: vehicle.diamondback.century (1) at (4017.26, 14489.8, 123.86)
|
||||
number_of_wheels = 2
|
||||
object_type =
|
||||
color = 50,96,242
|
||||
role_name = autopilot
|
||||
Frame 6 at 0.122666 seconds
|
||||
Create 2278: vehicle.seat.leon (1) at (3508.17, 7611.85, 120.002)
|
||||
number_of_wheels = 4
|
||||
object_type =
|
||||
color = 237,237,237
|
||||
role_name = autopilot
|
||||
Frame 8 at 0.171718 seconds
|
||||
Create 2279: vehicle.diamondback.century (1) at (3160, 3020.07, 120.002)
|
||||
number_of_wheels = 2
|
||||
object_type =
|
||||
color = 50,96,242
|
||||
role_name = autopilot
|
||||
Frame 10 at 0.219568 seconds
|
||||
Create 2280: vehicle.bmw.grandtourer (1) at (-5405.99, 3489.52, 125.545)
|
||||
number_of_wheels = 4
|
||||
object_type =
|
||||
color = 0,0,0
|
||||
role_name = autopilot
|
||||
Frame 2350 at 60.2805 seconds
|
||||
Destroy 2276
|
||||
Frame 2351 at 60.3057 seconds
|
||||
Destroy 2277
|
||||
Frame 2352 at 60.3293 seconds
|
||||
Destroy 2278
|
||||
Frame 2353 at 60.3531 seconds
|
||||
Destroy 2279
|
||||
Frame 2354 at 60.3753 seconds
|
||||
Destroy 2280
|
||||
|
||||
Frames: 2354
|
||||
Duration: 60.3753 seconds
|
||||
```
|
||||
From here we know the **date** and the **map** where the simulation was recorded.
|
||||
Then for each frame that has an event (create or destroy an actor, collisions) it shows that info. For creating actors we see the **Id** it has and some info about the actor to create. This is the **id** we need to specify in the **camera** option when replaying if we want to follow that actor during the replay.
|
||||
At the end we can see the **total time** of the recording and also the number of **frames** that were recorded.
|
||||
|
||||
In simulations whith a **hero actor** the collisions are automatically saved, so we can query a recorded file to see if any **hero actor** had collisions with some other actor. Currently the actor types we can use in the query are these:
|
||||
|
||||
* **h** = Hero
|
||||
* **v** = Vehicle
|
||||
* **w** = Walker
|
||||
* **t** = Traffic light
|
||||
* **o** = Other
|
||||
* **a** = Any
|
||||
|
||||
The collision query needs to know the type of actors involved in the collision. If we don't care we can specify **a** (any) for both. These are some examples:
|
||||
|
||||
* **a** **a**: will show all collisions recorded
|
||||
* **v** **v**: will show all collisions between vehicles
|
||||
* **v** **t**: will show all collisions between a vehicle and a traffic light
|
||||
* **v** **w**: will show all collisions between a vehicle and a walker
|
||||
* **v** **o**: will show all collisions between a vehicle and other actor, like static meshes
|
||||
* **h** **w**: will show all collisions between a hero and a walker
|
||||
|
||||
Currently only **hero actors** record the collisions, so first actor will be a hero always.
|
||||
|
||||
The API for querying the collisions is:
|
||||
|
||||
```py
|
||||
client.show_recorder_collisions("recording01.log", "a", "a")
|
||||
```
|
||||
|
||||
The output is something similar to this:
|
||||
|
||||
```
|
||||
Version: 1
|
||||
Map: Town05
|
||||
Date: 02/19/19 15:36:08
|
||||
|
||||
Time Types Id Actor 1 Id Actor 2
|
||||
16 v v 122 vehicle.yamaha.yzf 118 vehicle.dodge_charger.police
|
||||
27 v o 122 vehicle.yamaha.yzf 0
|
||||
|
||||
Frames: 790
|
||||
Duration: 46 seconds
|
||||
```
|
||||
|
||||
We can see there for each collision the **time** when happened, the **type** of the actors involved, and the **id and description** of each actor.
|
||||
|
||||
So, if we want to see what happened on that recording for the first collision where the hero actor was colliding with a vehicle, we could use this API:
|
||||
|
||||
```py
|
||||
client.replay_file("col2.log", 13, 0, 122)
|
||||
```
|
||||
We have started the replayer just a bit before the time of the collision, so we can see how it happened.
|
||||
Also, a value of 0 for the **duration** means to replay all the file (it is the default value).
|
||||
|
||||
We can see something like this then:
|
||||
|
||||
![collision](img/collision1.gif)
|
||||
|
||||
There is another API to get information about actors that has been blocked by something and can not follow its way. That could be good to find incidences in the simulation. The API is:
|
||||
|
||||
```py
|
||||
client.show_recorder_actors_blocked("recording01.log", min_time, min_distance)
|
||||
```
|
||||
|
||||
The parameters are:
|
||||
* **min_time**: the minimum time that an actor needs to be stopped to be considered as blocked (in seconds).
|
||||
* **min_distance**: the minimum distance to consider an actor to be stopped (in cm).
|
||||
|
||||
So, if we want to know which actor is stopped (moving less than 1 meter during 60 seconds), we could use something like:
|
||||
|
||||
```py
|
||||
client.show_recorder_actors_blocked("col3.log", 60, 100)
|
||||
```
|
||||
|
||||
The result can be something like (it is sorted by the duration):
|
||||
|
||||
```
|
||||
Version: 1
|
||||
Map: Town05
|
||||
Date: 02/19/19 15:45:01
|
||||
|
||||
Time Id Actor Duration
|
||||
36 173 vehicle.nissan.patrol 336
|
||||
75 104 vehicle.dodge_charger.police 295
|
||||
75 214 vehicle.chevrolet.impala 295
|
||||
234 76 vehicle.nissan.micra 134
|
||||
241 162 vehicle.audi.a2 128
|
||||
302 143 vehicle.bmw.grandtourer 67
|
||||
303 133 vehicle.nissan.micra 67
|
||||
303 167 vehicle.audi.a2 66
|
||||
302 80 vehicle.nissan.micra 67
|
||||
|
||||
Frames: 6985
|
||||
Duration: 374 seconds
|
||||
```
|
||||
|
||||
This lines tell us when an actor was stopped for at least the minimum time specified.
|
||||
For example the 6th line, the actor 143, at time 302 seconds, was stopped for 67 seconds.
|
||||
|
||||
We could check what happened that time with the next API command:
|
||||
|
||||
```py
|
||||
client.replay_file("col3.log", 302, 0, 143)
|
||||
```
|
||||
|
||||
![actor blocked](img/actor_blocked1.png)
|
||||
|
||||
We see there is some mess there that actually blocks the actor (red vehicle in the image).
|
||||
We can check also another actor with:
|
||||
|
||||
```py
|
||||
client.replay_file("col3.log", 75, 0, 104)
|
||||
```
|
||||
|
||||
![actor blocked](img/actor_blocked2.png)
|
||||
|
||||
We can see it is the same incidence but from another actor involved (police car).
|
||||
|
||||
The result is sorted by duration, so the actor that is blocked for more time comes first. We could check the first line, with Id 173 at time 36 seconds it get stopped for 336 seconds. We could check how it arrived to that situation replaying a few seconds before time 36.
|
||||
|
||||
```py
|
||||
client.replay_file("col3.log", 34, 0, 173)
|
||||
```
|
||||
|
||||
![accident](img/accident.gif)
|
||||
|
||||
We can see then the responsible of the incident.
|
||||
|
||||
#### Sample PY scripts to use with the recording / replaying system
|
||||
|
||||
There are some scripts you could use:
|
||||
|
||||
* **start_recording.py**: this will start recording, and optionally you can spawn several actors and define how much time you want to record.
|
||||
* **-f**: filename of write
|
||||
* **-n**: vehicles to spawn (optional, 10 by default)
|
||||
* **-t**: duration of the recording (optional)
|
||||
* **start_replaying.py**: this will start a replay of a file. We can define the starting time, duration and also an actor to follow.
|
||||
* **-f**: filename of write
|
||||
* **-s**: starting time (optional, by default from start)
|
||||
* **-d**: duration (optional, by default all)
|
||||
* **-c**: actor to follow (id) (optional)
|
||||
* **show_recorder_collisions.py**: this will show all the collisions hapenned while recording (currently only involved by hero actors).
|
||||
* **-f**: filename of write
|
||||
* **-t**: two letters definning the types of the actors involved, for example: -t aa
|
||||
* **h** = Hero
|
||||
* **v** = Vehicle
|
||||
* **w** = Walker
|
||||
* **t** = Traffic light
|
||||
* **o** = Other
|
||||
* **a** = Any
|
||||
* **show_recorder_actors_blocked.py**: this will show all the actors that are blocked (stopped) in the recorder. We can define the time and distance to be considered as blocked.
|
||||
* **-f**: filename of write
|
||||
* **-t**: minimum seconds stopped to be considered as blocked (optional)
|
||||
* **-d**: minimum distance to be considered stopped (optional)
|
||||
|
||||
|
||||
|
|
|
@ -51,10 +51,12 @@ pipeline {
|
|||
stage('Package') {
|
||||
steps {
|
||||
sh 'make package'
|
||||
sh 'make export-maps ARGS="--map=/Game/Carla/Maps/Town06 --file=Town06"'
|
||||
}
|
||||
post {
|
||||
always {
|
||||
archiveArtifacts 'Dist/*.tar.gz'
|
||||
archiveArtifacts 'ExportedMaps/*.tar.gz'
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -48,6 +48,30 @@ namespace client {
|
|||
return World{_simulator->GetCurrentEpisode()};
|
||||
}
|
||||
|
||||
std::string StartRecorder(std::string name) {
|
||||
return _simulator->StartRecorder(name);
|
||||
}
|
||||
|
||||
void StopRecorder(void) {
|
||||
_simulator->StopRecorder();
|
||||
}
|
||||
|
||||
std::string ShowRecorderFileInfo(std::string name) {
|
||||
return _simulator->ShowRecorderFileInfo(name);
|
||||
}
|
||||
|
||||
std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
|
||||
return _simulator->ShowRecorderCollisions(name, type1, type2);
|
||||
}
|
||||
|
||||
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
|
||||
return _simulator->ShowRecorderActorsBlocked(name, min_time, min_distance);
|
||||
}
|
||||
|
||||
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id) {
|
||||
return _simulator->ReplayFile(name, start, duration, follow_id);
|
||||
}
|
||||
|
||||
private:
|
||||
|
||||
std::shared_ptr<detail::Simulator> _simulator;
|
||||
|
|
|
@ -266,6 +266,30 @@ namespace detail {
|
|||
_pimpl->AsyncCall("draw_debug_shape", shape);
|
||||
}
|
||||
|
||||
std::string Client::StartRecorder(std::string name) {
|
||||
return _pimpl->CallAndWait<std::string>("start_recorder", name);
|
||||
}
|
||||
|
||||
void Client::StopRecorder(void) {
|
||||
return _pimpl->AsyncCall("stop_recorder");
|
||||
}
|
||||
|
||||
std::string Client::ShowRecorderFileInfo(std::string name) {
|
||||
return _pimpl->CallAndWait<std::string>("show_recorder_file_info", name);
|
||||
}
|
||||
|
||||
std::string Client::ShowRecorderCollisions(std::string name, char type1, char type2) {
|
||||
return _pimpl->CallAndWait<std::string>("show_recorder_collisions", name, type1, type2);
|
||||
}
|
||||
|
||||
std::string Client::ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
|
||||
return _pimpl->CallAndWait<std::string>("show_recorder_actors_blocked", name, min_time, min_distance);
|
||||
}
|
||||
|
||||
std::string Client::ReplayFile(std::string name, double start, double duration, uint32_t follow_id) {
|
||||
return _pimpl->CallAndWait<std::string>("replay_file", name, start, duration, follow_id);
|
||||
}
|
||||
|
||||
} // namespace detail
|
||||
} // namespace client
|
||||
} // namespace carla
|
||||
|
|
|
@ -164,6 +164,13 @@ namespace detail {
|
|||
|
||||
void DrawDebugShape(const rpc::DebugShape &shape);
|
||||
|
||||
std::string StartRecorder(std::string name);
|
||||
void StopRecorder(void);
|
||||
std::string ShowRecorderFileInfo(std::string name);
|
||||
std::string ShowRecorderCollisions(std::string name, char type1, char type2);
|
||||
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance);
|
||||
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id);
|
||||
|
||||
std::vector<rpc::actor_id_type> GetGroupTrafficLights(const rpc::Actor &trafficLight);
|
||||
|
||||
private:
|
||||
|
|
|
@ -229,6 +229,36 @@ namespace detail {
|
|||
void ApplyPhysicsControlToVehicle(Vehicle &vehicle, const rpc::VehiclePhysicsControl &physicsControl) {
|
||||
_client.ApplyPhysicsControlToVehicle(vehicle.Serialize(), physicsControl);
|
||||
}
|
||||
/// @}
|
||||
// =========================================================================
|
||||
/// @name Operations with the recorder
|
||||
// =========================================================================
|
||||
/// @{
|
||||
|
||||
std::string StartRecorder(std::string name) {
|
||||
return _client.StartRecorder(std::move(name));
|
||||
}
|
||||
|
||||
void StopRecorder(void) {
|
||||
_client.StopRecorder();
|
||||
}
|
||||
|
||||
std::string ShowRecorderFileInfo(std::string name) {
|
||||
return _client.ShowRecorderFileInfo(std::move(name));
|
||||
}
|
||||
|
||||
std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
|
||||
return _client.ShowRecorderCollisions(std::move(name), type1, type2);
|
||||
}
|
||||
|
||||
std::string ShowRecorderActorsBlocked(std::string name, double min_time, double min_distance) {
|
||||
return _client.ShowRecorderActorsBlocked(std::move(name), min_time, min_distance);
|
||||
}
|
||||
|
||||
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id) {
|
||||
return _client.ReplayFile(std::move(name), start, duration, follow_id);
|
||||
}
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
/// @name Operations with sensors
|
||||
|
|
|
@ -109,6 +109,10 @@ namespace opendrive {
|
|||
|
||||
mapBuilder.SetGeoReference(open_drive_road.geoReference);
|
||||
|
||||
mapBuilder.SetTrafficGroupData(open_drive_road.trafficlightgroups);
|
||||
|
||||
mapBuilder.SetTrafficSignData(open_drive_road.trafficsigns);
|
||||
|
||||
// Generate road and junction information
|
||||
using junction_data_t = std::map<int, std::map<int, std::vector<carla::road::lane_junction_t>>>;
|
||||
using road_data_t = std::map<int, carla::opendrive::types::RoadInformation *>;
|
||||
|
@ -139,15 +143,14 @@ namespace opendrive {
|
|||
RoadGeneralInfo->SetLanesOffset(s, a);
|
||||
}
|
||||
|
||||
for(auto &&elevation : it->second->road_profiles.elevation_profile) {
|
||||
for (auto &&elevation : it->second->road_profiles.elevation_profile) {
|
||||
roadSegment.MakeInfo<carla::road::element::RoadElevationInfo>(
|
||||
elevation.start_position,
|
||||
elevation.start_position,
|
||||
elevation.elevation,
|
||||
elevation.slope,
|
||||
elevation.vertical_curvature,
|
||||
elevation.curvature_change
|
||||
);
|
||||
elevation.start_position,
|
||||
elevation.start_position,
|
||||
elevation.elevation,
|
||||
elevation.slope,
|
||||
elevation.vertical_curvature,
|
||||
elevation.curvature_change);
|
||||
}
|
||||
|
||||
std::map<int, int> leftLanesGoToSuccessor, leftLanesGoToPredecessor;
|
||||
|
|
|
@ -14,6 +14,9 @@
|
|||
#include "GeometryParser.h"
|
||||
#include "LaneParser.h"
|
||||
|
||||
#include "TrafficGroupParser.h"
|
||||
#include "TrafficSignParser.h"
|
||||
|
||||
#include "./pugixml/pugixml.hpp"
|
||||
|
||||
#include <iostream>
|
||||
|
@ -86,6 +89,18 @@ struct OpenDriveParser {
|
|||
carla::opendrive::parser::JunctionParser::Parse(junction, out_open_drive_data.junctions);
|
||||
}
|
||||
|
||||
for (pugi::xml_node tlgroup = xmlDoc.child("OpenDRIVE").child("tlGroup");
|
||||
tlgroup;
|
||||
tlgroup = tlgroup.next_sibling("tlGroup")) {
|
||||
carla::opendrive::parser::TrafficGroupParser::Parse(tlgroup, out_open_drive_data.trafficlightgroups);
|
||||
}
|
||||
|
||||
for (pugi::xml_node trafficsigns = xmlDoc.child("OpenDRIVE").child("trafficsign");
|
||||
trafficsigns;
|
||||
trafficsigns = trafficsigns.next_sibling("trafficsign")) {
|
||||
carla::opendrive::parser::TrafficSignParser::Parse(trafficsigns, out_open_drive_data.trafficsigns);
|
||||
}
|
||||
|
||||
out_open_drive_data.geoReference = xmlDoc.child("OpenDRIVE").child("header").child_value("geoReference");
|
||||
|
||||
return true;
|
||||
|
|
|
@ -0,0 +1,65 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "TrafficGroupParser.h"
|
||||
#include <iostream>
|
||||
|
||||
void carla::opendrive::parser::TrafficGroupParser::Parse(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::TrafficLightGroup> &out_trafficLights) {
|
||||
carla::opendrive::parser::TrafficGroupParser parser;
|
||||
carla::opendrive::types::TrafficLightGroup traffic_light_group;
|
||||
|
||||
traffic_light_group.red_time = std::atoi(xmlNode.attribute("redTime").value());
|
||||
traffic_light_group.yellow_time = std::atoi(xmlNode.attribute("yellowTime").value());
|
||||
traffic_light_group.green_time = std::atoi(xmlNode.attribute("greenTime").value());
|
||||
|
||||
parser.ParseTrafficLight(xmlNode, traffic_light_group.traffic_lights);
|
||||
out_trafficLights.emplace_back(traffic_light_group);
|
||||
}
|
||||
|
||||
void carla::opendrive::parser::TrafficGroupParser::ParseTrafficLight(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::TrafficLight> &out_trafficLight) {
|
||||
|
||||
for (pugi::xml_node trafficlight = xmlNode.child("trafficlight");
|
||||
trafficlight;
|
||||
trafficlight = trafficlight.next_sibling("trafficlight")) {
|
||||
carla::opendrive::types::TrafficLight jTrafficlight;
|
||||
|
||||
jTrafficlight.x_pos = std::stod(trafficlight.attribute("xPos").value());
|
||||
jTrafficlight.y_pos = std::stod(trafficlight.attribute("yPos").value());
|
||||
jTrafficlight.z_pos = std::stod(trafficlight.attribute("zPos").value());
|
||||
jTrafficlight.x_rot = std::stod(trafficlight.attribute("xRot").value());
|
||||
jTrafficlight.y_rot = std::stod(trafficlight.attribute("yRot").value());
|
||||
jTrafficlight.z_rot = std::stod(trafficlight.attribute("zRot").value());
|
||||
|
||||
ParseBoxAreas(trafficlight, jTrafficlight.box_areas);
|
||||
|
||||
out_trafficLight.emplace_back(jTrafficlight);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void carla::opendrive::parser::TrafficGroupParser::ParseBoxAreas(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::BoxComponent> &out_boxcomponent) {
|
||||
for (pugi::xml_node boxcomponent = xmlNode.child("tfBox");
|
||||
boxcomponent;
|
||||
boxcomponent = boxcomponent.next_sibling("tfBox")) {
|
||||
carla::opendrive::types::BoxComponent jBoxComponent;
|
||||
|
||||
jBoxComponent.x_pos = std::stod(boxcomponent.attribute("xPos").value());
|
||||
jBoxComponent.y_pos = std::stod(boxcomponent.attribute("yPos").value());
|
||||
jBoxComponent.z_pos = std::stod(boxcomponent.attribute("zPos").value());
|
||||
jBoxComponent.x_rot = std::stod(boxcomponent.attribute("xRot").value());
|
||||
jBoxComponent.y_rot = std::stod(boxcomponent.attribute("yRot").value());
|
||||
jBoxComponent.z_rot = std::stod(boxcomponent.attribute("zRot").value());
|
||||
|
||||
out_boxcomponent.emplace_back(jBoxComponent);
|
||||
}
|
||||
|
||||
}
|
|
@ -0,0 +1,38 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "../types.h"
|
||||
|
||||
#include "./pugixml/pugixml.hpp"
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
namespace parser {
|
||||
|
||||
class TrafficGroupParser {
|
||||
private:
|
||||
|
||||
void ParseTrafficLight(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::TrafficLight> &out_trafficLights);
|
||||
|
||||
void ParseBoxAreas(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::BoxComponent> &out_boxareas);
|
||||
|
||||
public:
|
||||
|
||||
static void Parse(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::TrafficLightGroup> &out_trafficlightgroup);
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
}
|
||||
}
|
|
@ -0,0 +1,46 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "TrafficSignParser.h"
|
||||
#include <iostream>
|
||||
|
||||
void carla::opendrive::parser::TrafficSignParser::Parse(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::TrafficSign> &out_trafficsigns) {
|
||||
carla::opendrive::parser::TrafficSignParser parser;
|
||||
carla::opendrive::types::TrafficSign trafficsign;
|
||||
|
||||
trafficsign.speed = std::atoi(xmlNode.attribute("speed").value());
|
||||
trafficsign.x_pos = std::stod(xmlNode.attribute("xPos").value());
|
||||
trafficsign.y_pos = std::stod(xmlNode.attribute("yPos").value());
|
||||
trafficsign.z_pos = std::stod(xmlNode.attribute("zPos").value());
|
||||
trafficsign.x_rot = std::stod(xmlNode.attribute("xRot").value());
|
||||
trafficsign.y_rot = std::stod(xmlNode.attribute("yRot").value());
|
||||
trafficsign.z_rot = std::stod(xmlNode.attribute("zRot").value());
|
||||
|
||||
parser.ParseBoxAreas(xmlNode, trafficsign.box_areas);
|
||||
out_trafficsigns.emplace_back(trafficsign);
|
||||
}
|
||||
|
||||
void carla::opendrive::parser::TrafficSignParser::ParseBoxAreas(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::BoxComponent> &out_boxcomponent) {
|
||||
for (pugi::xml_node boxcomponent = xmlNode.child("tsBox");
|
||||
boxcomponent;
|
||||
boxcomponent = boxcomponent.next_sibling("tsBox")) {
|
||||
carla::opendrive::types::BoxComponent jBoxComponent;
|
||||
|
||||
jBoxComponent.x_pos = std::stod(boxcomponent.attribute("xPos").value());
|
||||
jBoxComponent.y_pos = std::stod(boxcomponent.attribute("yPos").value());
|
||||
jBoxComponent.z_pos = std::stod(boxcomponent.attribute("zPos").value());
|
||||
jBoxComponent.x_rot = std::stod(boxcomponent.attribute("xRot").value());
|
||||
jBoxComponent.y_rot = std::stod(boxcomponent.attribute("yRot").value());
|
||||
jBoxComponent.z_rot = std::stod(boxcomponent.attribute("zRot").value());
|
||||
|
||||
out_boxcomponent.emplace_back(jBoxComponent);
|
||||
}
|
||||
|
||||
}
|
|
@ -0,0 +1,34 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "../types.h"
|
||||
|
||||
#include "./pugixml/pugixml.hpp"
|
||||
|
||||
namespace carla {
|
||||
namespace opendrive {
|
||||
namespace parser {
|
||||
|
||||
class TrafficSignParser {
|
||||
private:
|
||||
|
||||
void ParseBoxAreas(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::BoxComponent> &out_boxareas);
|
||||
|
||||
public:
|
||||
|
||||
static void Parse(
|
||||
const pugi::xml_node &xmlNode,
|
||||
std::vector<carla::opendrive::types::TrafficSign> &out_trafficsigns);
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
}
|
||||
}
|
|
@ -236,12 +236,76 @@ namespace types {
|
|||
std::vector<JunctionConnection> connections;
|
||||
};
|
||||
|
||||
struct BoxComponent {
|
||||
union {
|
||||
struct { double x_pos, y_pos, z_pos;
|
||||
};
|
||||
double pos[3];
|
||||
};
|
||||
union {
|
||||
struct { double x_rot, y_rot, z_rot;
|
||||
};
|
||||
double rot[3];
|
||||
};
|
||||
double scale;
|
||||
BoxComponent() : pos{0.0, 0.0, 0.0},
|
||||
rot{0.0, 0.0, 0.0},
|
||||
scale(1.0) {}
|
||||
};
|
||||
|
||||
struct TrafficLight {
|
||||
union {
|
||||
struct { double x_pos, y_pos, z_pos;
|
||||
};
|
||||
double pos[3];
|
||||
};
|
||||
union {
|
||||
struct { double x_rot, y_rot, z_rot;
|
||||
};
|
||||
double rot[3];
|
||||
};
|
||||
double scale;
|
||||
std::vector<BoxComponent> box_areas;
|
||||
|
||||
TrafficLight() : pos{0.0, 0.0, 0.0},
|
||||
rot{0.0, 0.0, 0.0},
|
||||
scale(1.0) {}
|
||||
};
|
||||
|
||||
struct TrafficLightGroup {
|
||||
std::vector<TrafficLight> traffic_lights;
|
||||
double red_time, yellow_time, green_time;
|
||||
};
|
||||
|
||||
struct TrafficSign {
|
||||
union {
|
||||
struct { double x_pos, y_pos, z_pos;
|
||||
};
|
||||
double pos[3];
|
||||
};
|
||||
union {
|
||||
struct { double x_rot, y_rot, z_rot;
|
||||
};
|
||||
double rot[3];
|
||||
};
|
||||
double scale;
|
||||
int speed;
|
||||
std::vector<BoxComponent> box_areas;
|
||||
|
||||
TrafficSign() : pos{0.0, 0.0, 0.0},
|
||||
rot{0.0, 0.0, 0.0},
|
||||
scale(1.0),
|
||||
speed(30) {}
|
||||
};
|
||||
|
||||
/////////////////////////////////////////////////////////////////
|
||||
|
||||
struct OpenDriveData {
|
||||
std::string geoReference;
|
||||
std::vector<RoadInformation> roads;
|
||||
std::vector<Junction> junctions;
|
||||
std::vector<TrafficLightGroup> trafficlightgroups;
|
||||
std::vector<TrafficSign> trafficsigns;
|
||||
};
|
||||
|
||||
struct Waypoint {
|
||||
|
|
|
@ -27,6 +27,14 @@ namespace road {
|
|||
_map_data.SetGeoReference(geoReference);
|
||||
}
|
||||
|
||||
void SetTrafficGroupData(const std::vector<opendrive::types::TrafficLightGroup> &trafficLightData) {
|
||||
_map_data.SetTrafficLightData(trafficLightData);
|
||||
}
|
||||
|
||||
void SetTrafficSignData(const std::vector<opendrive::types::TrafficSign> &trafficSignData) {
|
||||
_map_data.SetTrafficSignData(trafficSignData);
|
||||
}
|
||||
|
||||
SharedPtr<Map> Build();
|
||||
|
||||
private:
|
||||
|
|
|
@ -10,6 +10,7 @@
|
|||
#include "carla/ListView.h"
|
||||
#include "carla/NonCopyable.h"
|
||||
#include "carla/road/element/RoadSegment.h"
|
||||
#include "carla/opendrive/types.h"
|
||||
|
||||
#include <boost/iterator/transform_iterator.hpp>
|
||||
|
||||
|
@ -56,6 +57,14 @@ namespace road {
|
|||
return _geo_reference;
|
||||
}
|
||||
|
||||
const std::vector<opendrive::types::TrafficLightGroup> &GetTrafficGroups() const {
|
||||
return _traffic_groups;
|
||||
}
|
||||
|
||||
const std::vector<opendrive::types::TrafficSign> &GetTrafficSigns() const {
|
||||
return _traffic_signs;
|
||||
}
|
||||
|
||||
auto GetRoadSegments() const {
|
||||
using const_ref = const element::RoadSegment &;
|
||||
auto get = [](auto &pair) -> const_ref { return *pair.second; };
|
||||
|
@ -78,6 +87,14 @@ namespace road {
|
|||
_geo_reference = geoReference;
|
||||
}
|
||||
|
||||
void SetTrafficLightData(const std::vector<opendrive::types::TrafficLightGroup> &trafficLightData) {
|
||||
_traffic_groups = trafficLightData;
|
||||
}
|
||||
|
||||
void SetTrafficSignData(const std::vector<opendrive::types::TrafficSign> &trafficSignData) {
|
||||
_traffic_signs = trafficSignData;
|
||||
}
|
||||
|
||||
std::string _geo_reference;
|
||||
|
||||
std::vector<lane_junction_t> _junction_information;
|
||||
|
@ -85,6 +102,10 @@ namespace road {
|
|||
std::unordered_map<
|
||||
element::id_type,
|
||||
std::unique_ptr<element::RoadSegment>> _elements;
|
||||
|
||||
std::vector<opendrive::types::TrafficLightGroup> _traffic_groups;
|
||||
|
||||
std::vector<opendrive::types::TrafficSign> _traffic_signs;
|
||||
};
|
||||
|
||||
} // namespace road
|
||||
|
|
|
@ -31,6 +31,11 @@ Use ARROWS or WASD keys for control.
|
|||
|
||||
R : toggle recording images to disk
|
||||
|
||||
CTRL + R : toggle recording of simulation (replacing any previous)
|
||||
CTRL + P : start replaying last recorded simulation
|
||||
CTRL + + : increments the start time of the replay by 1 second (+SHIFT = 10 seconds)
|
||||
CTRL + - : decrements the start time of the replay by 1 second (+SHIFT = 10 seconds)
|
||||
|
||||
F1 : toggle HUD
|
||||
H/? : toggle help
|
||||
ESC : quit
|
||||
|
@ -104,6 +109,8 @@ try:
|
|||
from pygame.locals import K_r
|
||||
from pygame.locals import K_s
|
||||
from pygame.locals import K_w
|
||||
from pygame.locals import K_MINUS
|
||||
from pygame.locals import K_EQUALS
|
||||
except ImportError:
|
||||
raise RuntimeError('cannot import pygame, make sure pygame package is installed')
|
||||
|
||||
|
@ -149,6 +156,8 @@ class World(object):
|
|||
self._actor_filter = actor_filter
|
||||
self.restart()
|
||||
self.world.on_tick(hud.on_world_tick)
|
||||
self.recording_enabled = False
|
||||
self.recording_start = 0
|
||||
|
||||
def restart(self):
|
||||
# Keep same camera config if the camera manager exists.
|
||||
|
@ -196,6 +205,11 @@ class World(object):
|
|||
self.camera_manager.render(display)
|
||||
self.hud.render(display)
|
||||
|
||||
def destroySensors(self):
|
||||
self.camera_manager.sensor.destroy()
|
||||
self.camera_manager.sensor = None
|
||||
self.camera_manager._index = None
|
||||
|
||||
def destroy(self):
|
||||
actors = [
|
||||
self.camera_manager.sensor,
|
||||
|
@ -207,7 +221,6 @@ class World(object):
|
|||
if actor is not None:
|
||||
actor.destroy()
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- KeyboardControl -----------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
@ -228,7 +241,7 @@ class KeyboardControl(object):
|
|||
self._steer_cache = 0.0
|
||||
world.hud.notification("Press 'H' or '?' for help.", seconds=4.0)
|
||||
|
||||
def parse_events(self, world, clock):
|
||||
def parse_events(self, client, world, clock):
|
||||
for event in pygame.event.get():
|
||||
if event.type == pygame.QUIT:
|
||||
return True
|
||||
|
@ -251,8 +264,43 @@ class KeyboardControl(object):
|
|||
world.camera_manager.next_sensor()
|
||||
elif event.key > K_0 and event.key <= K_9:
|
||||
world.camera_manager.set_sensor(event.key - 1 - K_0)
|
||||
elif event.key == K_r:
|
||||
elif event.key == K_r and not (pygame.key.get_mods() & KMOD_CTRL):
|
||||
world.camera_manager.toggle_recording()
|
||||
elif event.key == K_r and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
if (world.recording_enabled):
|
||||
client.stop_recorder()
|
||||
world.recording_enabled = False
|
||||
world.hud.notification("Recorder is OFF")
|
||||
else:
|
||||
client.start_recorder("manual_recording.rec")
|
||||
world.recording_enabled = True
|
||||
world.hud.notification("Recorder is ON")
|
||||
elif event.key == K_p and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
# stop recorder
|
||||
client.stop_recorder()
|
||||
world.recording_enabled = False
|
||||
# work around to fix camera at start of replaying
|
||||
currentIndex = world.camera_manager._index
|
||||
world.destroySensors()
|
||||
# disable autopilot
|
||||
self._autopilot_enabled = False
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
world.hud.notification("Replaying file 'manual_recording.rec'")
|
||||
# replayer
|
||||
client.replay_file("manual_recording.rec", world.recording_start, 0, 0)
|
||||
world.camera_manager.set_sensor(currentIndex)
|
||||
elif event.key == K_MINUS and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
if pygame.key.get_mods() & KMOD_SHIFT:
|
||||
world.recording_start -= 10
|
||||
else:
|
||||
world.recording_start -= 1
|
||||
world.hud.notification("Recording start time is %d" % (world.recording_start))
|
||||
elif event.key == K_EQUALS and (pygame.key.get_mods() & KMOD_CTRL):
|
||||
if pygame.key.get_mods() & KMOD_SHIFT:
|
||||
world.recording_start += 10
|
||||
else:
|
||||
world.recording_start += 1
|
||||
world.hud.notification("Recording start time is %d" % (world.recording_start))
|
||||
if isinstance(self._control, carla.VehicleControl):
|
||||
if event.key == K_q:
|
||||
self._control.gear = 1 if self._control.reverse else -1
|
||||
|
@ -264,7 +312,7 @@ class KeyboardControl(object):
|
|||
self._control.gear = max(-1, self._control.gear - 1)
|
||||
elif self._control.manual_gear_shift and event.key == K_PERIOD:
|
||||
self._control.gear = self._control.gear + 1
|
||||
elif event.key == K_p:
|
||||
elif event.key == K_p and not (pygame.key.get_mods() & KMOD_CTRL):
|
||||
self._autopilot_enabled = not self._autopilot_enabled
|
||||
world.player.set_autopilot(self._autopilot_enabled)
|
||||
world.hud.notification('Autopilot %s' % ('On' if self._autopilot_enabled else 'Off'))
|
||||
|
@ -722,7 +770,7 @@ def game_loop(args):
|
|||
clock = pygame.time.Clock()
|
||||
while True:
|
||||
clock.tick_busy_loop(60)
|
||||
if controller.parse_events(world, clock):
|
||||
if controller.parse_events(client, world, clock):
|
||||
return
|
||||
world.tick(clock)
|
||||
world.render(display)
|
||||
|
@ -730,6 +778,9 @@ def game_loop(args):
|
|||
|
||||
finally:
|
||||
|
||||
if (world and world.recording_enabled):
|
||||
client.stop_recorder()
|
||||
|
||||
if world is not None:
|
||||
world.destroy()
|
||||
|
||||
|
|
|
@ -1,3 +1,5 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
|
|
|
@ -0,0 +1,79 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('**/*%d.%d-%s.egg' % (
|
||||
sys.version_info.major,
|
||||
sys.version_info.minor,
|
||||
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-f', '--recorder_filename',
|
||||
metavar='F',
|
||||
default="test1.rec",
|
||||
help='recorder filename (test1.rec)')
|
||||
argparser.add_argument(
|
||||
'-t', '--time',
|
||||
metavar='T',
|
||||
default="30",
|
||||
type=float,
|
||||
help='minimum time to consider it is blocked')
|
||||
argparser.add_argument(
|
||||
'-d', '--distance',
|
||||
metavar='D',
|
||||
default="100",
|
||||
type=float,
|
||||
help='minimum distance to consider it is not moving (in cm)')
|
||||
args = argparser.parse_args()
|
||||
|
||||
try:
|
||||
|
||||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(60.0)
|
||||
|
||||
print(client.show_recorder_actors_blocked(args.recorder_filename, args.time, args.distance))
|
||||
|
||||
finally:
|
||||
pass
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
main()
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
print('\ndone.')
|
|
@ -0,0 +1,77 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('**/*%d.%d-%s.egg' % (
|
||||
sys.version_info.major,
|
||||
sys.version_info.minor,
|
||||
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-f', '--recorder_filename',
|
||||
metavar='F',
|
||||
default="test1.rec",
|
||||
help='recorder filename (test1.rec)')
|
||||
argparser.add_argument(
|
||||
'-t', '--types',
|
||||
metavar='T',
|
||||
default="aa",
|
||||
help='pair of types (a=any, h=hero, v=vehicle, w=walkers, t=trafficLight, o=others')
|
||||
args = argparser.parse_args()
|
||||
|
||||
try:
|
||||
|
||||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(60.0)
|
||||
|
||||
# types pattern samples:
|
||||
# -t aa == any to any == show every collision (the default)
|
||||
# -t vv == vehicle to vehicle == show every collision between vehicles only
|
||||
# -t vt == vehicle to traffic light == show every collision between a vehicle and a traffic light
|
||||
# -t hh == hero to hero == show collision between a hero and another hero
|
||||
print(client.show_recorder_collisions(args.recorder_filename, args.types[0], args.types[1]))
|
||||
|
||||
finally:
|
||||
pass
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
main()
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
print('\ndone.')
|
|
@ -0,0 +1,67 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('**/*%d.%d-%s.egg' % (
|
||||
sys.version_info.major,
|
||||
sys.version_info.minor,
|
||||
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-f', '--recorder_filename',
|
||||
metavar='F',
|
||||
default="test1.rec",
|
||||
help='recorder filename (test1.rec)')
|
||||
args = argparser.parse_args()
|
||||
|
||||
try:
|
||||
|
||||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(60.0)
|
||||
|
||||
print(client.show_recorder_file_info(args.recorder_filename))
|
||||
|
||||
finally:
|
||||
pass
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
main()
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
print('\ndone.')
|
|
@ -22,5 +22,11 @@ void export_client() {
|
|||
.def("get_client_version", &cc::Client::GetClientVersion)
|
||||
.def("get_server_version", CONST_CALL_WITHOUT_GIL(cc::Client, GetServerVersion))
|
||||
.def("get_world", &cc::Client::GetWorld)
|
||||
.def("start_recorder", CALL_WITHOUT_GIL_1(cc::Client, StartRecorder, std::string), (arg("name")))
|
||||
.def("stop_recorder", &cc::Client::StopRecorder)
|
||||
.def("show_recorder_file_info", CALL_WITHOUT_GIL_1(cc::Client, ShowRecorderFileInfo, std::string), (arg("name")))
|
||||
.def("show_recorder_collisions", CALL_WITHOUT_GIL_3(cc::Client, ShowRecorderCollisions, std::string, char, char), (arg("name"), arg("type1"), arg("type2")))
|
||||
.def("show_recorder_actors_blocked", CALL_WITHOUT_GIL_3(cc::Client, ShowRecorderActorsBlocked, std::string, float, float), (arg("name"), arg("min_time"), arg("min_distance")))
|
||||
.def("replay_file", CALL_WITHOUT_GIL_4(cc::Client, ReplayFile, std::string, float, float, int), (arg("name"), arg("time_start"), arg("duration"), arg("follow_id")))
|
||||
;
|
||||
}
|
||||
|
|
|
@ -18,6 +18,30 @@
|
|||
return self.fn(); \
|
||||
}
|
||||
|
||||
// Convenient for requests with 1 argument.
|
||||
#define CALL_WITHOUT_GIL_1(cls, fn, T1_) +[](cls &self, T1_ t1) { \
|
||||
carla::PythonUtil::ReleaseGIL unlock; \
|
||||
return self.fn(std::forward<T1_>(t1)); \
|
||||
}
|
||||
|
||||
// Convenient for requests with 2 arguments.
|
||||
#define CALL_WITHOUT_GIL_2(cls, fn, T1_, T2_) +[](cls &self, T1_ t1, T2_ t2) { \
|
||||
carla::PythonUtil::ReleaseGIL unlock; \
|
||||
return self.fn(std::forward<T1_>(t1), std::forward<T2_>(t2)); \
|
||||
}
|
||||
|
||||
// Convenient for requests with 3 arguments.
|
||||
#define CALL_WITHOUT_GIL_3(cls, fn, T1_, T2_, T3_) +[](cls &self, T1_ t1, T2_ t2, T3_ t3) { \
|
||||
carla::PythonUtil::ReleaseGIL unlock; \
|
||||
return self.fn(std::forward<T1_>(t1), std::forward<T2_>(t2), std::forward<T3_>(t3)); \
|
||||
}
|
||||
|
||||
// Convenient for requests with 4 arguments.
|
||||
#define CALL_WITHOUT_GIL_4(cls, fn, T1_, T2_, T3_, T4_) +[](cls &self, T1_ t1, T2_ t2, T3_ t3, T4_ t4) { \
|
||||
carla::PythonUtil::ReleaseGIL unlock; \
|
||||
return self.fn(std::forward<T1_>(t1), std::forward<T2_>(t2), std::forward<T3_>(t3), std::forward<T4_>(t4)); \
|
||||
}
|
||||
|
||||
// Convenient for const requests without arguments.
|
||||
#define CONST_CALL_WITHOUT_GIL(cls, fn) CALL_WITHOUT_GIL(const cls, fn)
|
||||
|
||||
|
|
|
@ -0,0 +1,143 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('**/*%d.%d-%s.egg' % (
|
||||
sys.version_info.major,
|
||||
sys.version_info.minor,
|
||||
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-n', '--number-of-vehicles',
|
||||
metavar='N',
|
||||
default=10,
|
||||
type=int,
|
||||
help='number of vehicles (default: 10)')
|
||||
argparser.add_argument(
|
||||
'-d', '--delay',
|
||||
metavar='D',
|
||||
default=2.0,
|
||||
type=float,
|
||||
help='delay in seconds between spawns (default: 2.0)')
|
||||
argparser.add_argument(
|
||||
'--safe',
|
||||
action='store_true',
|
||||
help='avoid spawning vehicles prone to accidents')
|
||||
argparser.add_argument(
|
||||
'-f', '--recorder_filename',
|
||||
metavar='F',
|
||||
default="test1.log",
|
||||
help='recorder filename (test1.log)')
|
||||
argparser.add_argument(
|
||||
'-t', '--recorder_time',
|
||||
metavar='T',
|
||||
default=0,
|
||||
type=int,
|
||||
help='recorder duration (auto-stop)')
|
||||
args = argparser.parse_args()
|
||||
|
||||
actor_list = []
|
||||
|
||||
try:
|
||||
|
||||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(2.0)
|
||||
world = client.get_world()
|
||||
blueprints = world.get_blueprint_library().filter('vehicle.*')
|
||||
|
||||
if args.safe:
|
||||
blueprints = [x for x in blueprints if int(x.get_attribute('number_of_wheels')) == 4]
|
||||
blueprints = [x for x in blueprints if not x.id.endswith('isetta')]
|
||||
|
||||
def try_spawn_random_vehicle_at(transform):
|
||||
blueprint = random.choice(blueprints)
|
||||
if blueprint.has_attribute('color'):
|
||||
color = random.choice(blueprint.get_attribute('color').recommended_values)
|
||||
blueprint.set_attribute('color', color)
|
||||
blueprint.set_attribute('role_name', 'autopilot')
|
||||
vehicle = world.try_spawn_actor(blueprint, transform)
|
||||
if vehicle is not None:
|
||||
actor_list.append(vehicle)
|
||||
vehicle.set_autopilot()
|
||||
print('spawned %r at %s' % (vehicle.type_id, transform.location))
|
||||
return True
|
||||
return False
|
||||
|
||||
# @todo Needs to be converted to list to be shuffled.
|
||||
spawn_points = list(world.get_map().get_spawn_points())
|
||||
random.shuffle(spawn_points)
|
||||
|
||||
print('found %d spawn points.' % len(spawn_points))
|
||||
|
||||
count = args.number_of_vehicles
|
||||
|
||||
print("Recording on file:", client.start_recorder(args.recorder_filename))
|
||||
|
||||
for spawn_point in spawn_points:
|
||||
if try_spawn_random_vehicle_at(spawn_point):
|
||||
count -= 1
|
||||
if count <= 0:
|
||||
break
|
||||
|
||||
while count > 0:
|
||||
time.sleep(args.delay)
|
||||
if try_spawn_random_vehicle_at(random.choice(spawn_points)):
|
||||
count -= 1
|
||||
|
||||
print('spawned %d vehicles, press Ctrl+C to exit.' % args.number_of_vehicles)
|
||||
|
||||
if (args.recorder_time > 0):
|
||||
time.sleep(args.recorder_time)
|
||||
else:
|
||||
while True:
|
||||
time.sleep(0.1)
|
||||
|
||||
finally:
|
||||
|
||||
print('\ndestroying %d actors' % len(actor_list))
|
||||
for actor in actor_list:
|
||||
actor.destroy()
|
||||
|
||||
print("Stop recording")
|
||||
client.stop_recorder()
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
main()
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
print('\ndone.')
|
|
@ -0,0 +1,85 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
import glob
|
||||
import os
|
||||
import sys
|
||||
|
||||
try:
|
||||
sys.path.append(glob.glob('**/*%d.%d-%s.egg' % (
|
||||
sys.version_info.major,
|
||||
sys.version_info.minor,
|
||||
'win-amd64' if os.name == 'nt' else 'linux-x86_64'))[0])
|
||||
except IndexError:
|
||||
pass
|
||||
|
||||
import carla
|
||||
|
||||
import argparse
|
||||
import random
|
||||
import time
|
||||
|
||||
|
||||
def main():
|
||||
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'--host',
|
||||
metavar='H',
|
||||
default='127.0.0.1',
|
||||
help='IP of the host server (default: 127.0.0.1)')
|
||||
argparser.add_argument(
|
||||
'-p', '--port',
|
||||
metavar='P',
|
||||
default=2000,
|
||||
type=int,
|
||||
help='TCP port to listen to (default: 2000)')
|
||||
argparser.add_argument(
|
||||
'-s', '--start',
|
||||
metavar='S',
|
||||
default=0.0,
|
||||
type=float,
|
||||
help='starting time (default: 0.0)')
|
||||
argparser.add_argument(
|
||||
'-d', '--duration',
|
||||
metavar='D',
|
||||
default=0.0,
|
||||
type=float,
|
||||
help='duration (default: 0.0)')
|
||||
argparser.add_argument(
|
||||
'-f', '--recorder_filename',
|
||||
metavar='F',
|
||||
default="test1.log",
|
||||
help='recorder filename (test1.log)')
|
||||
argparser.add_argument(
|
||||
'-c', '--camera',
|
||||
metavar='C',
|
||||
default=0,
|
||||
type=int,
|
||||
help='camera follows an actor (ex: 82)')
|
||||
args = argparser.parse_args()
|
||||
|
||||
try:
|
||||
|
||||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(60.0)
|
||||
|
||||
print(client.replay_file(args.recorder_filename, args.start, args.duration, args.camera))
|
||||
|
||||
finally:
|
||||
pass
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
try:
|
||||
main()
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
print('\ndone.')
|
|
@ -0,0 +1,191 @@
|
|||
#!/usr/bin/env python
|
||||
|
||||
# Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma de
|
||||
# Barcelona (UAB).
|
||||
#
|
||||
# This work is licensed under the terms of the MIT license.
|
||||
# For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
"""Generate map from FBX"""
|
||||
|
||||
import os
|
||||
import json
|
||||
import subprocess
|
||||
import shutil
|
||||
import argparse
|
||||
|
||||
|
||||
if os.name == 'nt':
|
||||
sys_name = 'Win64'
|
||||
elif os.name == 'posix':
|
||||
sys_name = 'Linux'
|
||||
|
||||
|
||||
def main():
|
||||
if(args.force):
|
||||
generate_all_maps_but_list([])
|
||||
else:
|
||||
maps = get_map_names()
|
||||
generate_all_maps_but_list(maps)
|
||||
|
||||
|
||||
def get_map_names():
|
||||
maps = []
|
||||
dirname = os.getcwd()
|
||||
map_place = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "Content", "Carla", "ExportedMaps")
|
||||
for filename in os.listdir(map_place):
|
||||
if filename.endswith('.umap'):
|
||||
maps.append(filename)
|
||||
return maps
|
||||
|
||||
def generate_all_maps_but_list(existent_maps):
|
||||
map_name = ""
|
||||
dirname = os.getcwd()
|
||||
fbx_place = os.path.join(dirname, "..", "..", "RoadRunnerFiles")
|
||||
for x in os.walk(fbx_place):
|
||||
map_name = os.path.basename(x[0])
|
||||
if map_name != "RoadRunnerFiles":
|
||||
if not any(ext in "%s.umap" % map_name for ext in existent_maps):
|
||||
print("Found map in fbx folder: %s" % map_name)
|
||||
import_assets_commandlet(map_name)
|
||||
#move_uassets(map_name)
|
||||
print("Generating map asset for %s" % map_name)
|
||||
generate_map(map_name)
|
||||
print("Cleaning up directories")
|
||||
cleanup_assets(map_name)
|
||||
print("Finished %s" % map_name)
|
||||
else:
|
||||
print("WARNING: Found %s map in Content folder, skipping. Use \"--force\" to override\n" % map_name)
|
||||
|
||||
def parse_arguments():
|
||||
argparser = argparse.ArgumentParser(
|
||||
description=__doc__)
|
||||
argparser.add_argument(
|
||||
'-f', '--force',
|
||||
action='store_true',
|
||||
help='Force import. Will override maps with the same name')
|
||||
argparser.add_argument(
|
||||
'-m', '--map',
|
||||
metavar='M',
|
||||
type=str,
|
||||
help='Map to import. If empty, all maps in the folder will be loaded')
|
||||
argparser.add_argument(
|
||||
'--usecarlamats',
|
||||
action='store_true',
|
||||
help='Avoid using RoadRunner materials. Use materials provided by Carla instead')
|
||||
return argparser.parse_args()
|
||||
|
||||
|
||||
def cleanup_assets(map_name):
|
||||
dirname = os.getcwd()
|
||||
content_folder = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4" , "Content", "Carla")
|
||||
origin_folder = os.path.join(content_folder, "Static", "Imported", map_name)
|
||||
for filename in os.listdir(origin_folder):
|
||||
if map_name in filename:
|
||||
removal_path = os.path.join(origin_folder, filename)
|
||||
os.remove(removal_path)
|
||||
|
||||
|
||||
def import_assets_commandlet(map_name):
|
||||
generate_json(map_name, "importsetting.json")
|
||||
dirname = os.getcwd()
|
||||
commandlet_name = "ImportAssets"
|
||||
import_settings = os.path.join(dirname, "importsetting.json")
|
||||
commandlet_arguments = "-importSettings=\"%s\" -AllowCommandletRendering -nosourcecontrol -replaceexisting" % import_settings
|
||||
|
||||
file_xodr_origin = os.path.join(dirname, "..", "..", "RoadRunnerFiles", map_name, "%s.xodr" % map_name)
|
||||
file_xodr_dest = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "Content", "Carla", "Maps", "OpenDrive", "%s.xodr" % map_name)
|
||||
|
||||
shutil.copy2(file_xodr_origin, file_xodr_dest)
|
||||
invoke_commandlet(commandlet_name, commandlet_arguments)
|
||||
#Clean up
|
||||
os.remove("importsetting.json")
|
||||
|
||||
def generate_map(map_name):
|
||||
commandlet_name = "MapProcess"
|
||||
commandlet_arguments = "-mapname=\"%s\"" % map_name
|
||||
if args.usecarlamats:
|
||||
commandlet_arguments += " -use-carla-materials"
|
||||
invoke_commandlet(commandlet_name, commandlet_arguments)
|
||||
|
||||
#This line might be needed if Epic tells us anything about the current way of doing the movement. It shouldn't but just in case...
|
||||
def move_uassets(map_name):
|
||||
dirname = os.getcwd()
|
||||
content_folder = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4" , "Content", "Carla")
|
||||
origin_folder = os.path.join(content_folder, "Static", map_name)
|
||||
dest_path = ""
|
||||
src_path = ""
|
||||
marking_dir = os.path.join(content_folder, "Static", "RoadLines", "%sLaneMarking" % map_name)
|
||||
road_dir = os.path.join(content_folder, "Static", "Road", "Roads%s" % map_name)
|
||||
terrain_dir = os.path.join(content_folder, "Static", "Terrain", "%sTerrain" % map_name)
|
||||
if not os.path.exists(marking_dir):
|
||||
os.makedirs(marking_dir)
|
||||
if not os.path.exists(road_dir):
|
||||
os.makedirs(road_dir)
|
||||
if not os.path.exists(terrain_dir):
|
||||
os.makedirs(terrain_dir)
|
||||
for filename in os.listdir(origin_folder):
|
||||
if "MarkingNode" in filename:
|
||||
dest_path = os.path.join(marking_dir, filename)
|
||||
if "RoadNode" in filename:
|
||||
dest_path = os.path.join(road_dir, filename)
|
||||
if "TerrainNode" in filename:
|
||||
dest_path = os.path.join(terrain_dir, filename)
|
||||
src_path = os.path.join(content_folder, "Static", map_name, filename)
|
||||
os.rename(src_path, dest_path)
|
||||
|
||||
|
||||
|
||||
def invoke_commandlet(name, arguments):
|
||||
ue4_path = os.environ['UE4_ROOT']
|
||||
dirname = os.getcwd()
|
||||
editor_path = "%s/Engine/Binaries/%s/UE4Editor" % (ue4_path, sys_name)
|
||||
uproject_path = os.path.join(dirname, "..", "..", "Unreal", "CarlaUE4", "CarlaUE4.uproject")
|
||||
full_command = "%s %s -run=%s %s" % (editor_path, uproject_path, name, arguments)
|
||||
subprocess.check_call([full_command], shell=True)
|
||||
|
||||
|
||||
def generate_json(map_name, json_file):
|
||||
with open(json_file, "a+") as fh:
|
||||
import_groups = []
|
||||
file_names = []
|
||||
import_settings = []
|
||||
fbx_path = os.path.join("..", "..", "RoadRunnerFiles", map_name, "%s.fbx" % map_name)
|
||||
file_names.append(fbx_path)
|
||||
|
||||
import_settings.append({
|
||||
"bImportMesh": 1,
|
||||
"bConvertSceneUnit": 1,
|
||||
"bConvertScene": 1,
|
||||
"bCombineMeshes": 1,
|
||||
"bImportTextures": 1,
|
||||
"bImportMaterials": 1,
|
||||
"bRemoveDegenerates":1,
|
||||
"AnimSequenceImportData": {},
|
||||
"SkeletalMeshImportData": {},
|
||||
"TextureImportData": {},
|
||||
"StaticMeshImportData": {
|
||||
"bRemoveDegenerates": 1,
|
||||
"bAutoGenerateCollision": 0,
|
||||
"bCombineMeshes":0
|
||||
}
|
||||
})
|
||||
dest_path = "/Game/Carla/Static/Imported/%s" % map_name
|
||||
import_groups.append({
|
||||
"ImportSettings": import_settings,
|
||||
"FactoryName": "FbxFactory",
|
||||
"DestinationPath": dest_path,
|
||||
"bReplaceExisting": "true",
|
||||
"FileNames": file_names
|
||||
})
|
||||
fh.write(json.dumps({"ImportGroups": import_groups}))
|
||||
fh.close()
|
||||
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
try:
|
||||
args = parse_arguments()
|
||||
main()
|
||||
finally:
|
||||
print('\ndone.')
|
|
@ -0,0 +1,34 @@
|
|||
This is the place where the generate_map.py will look for the maps.
|
||||
|
||||
The structure must be one folder per map, with the same name as the .fbx and .xodr files that will be inside said folder.
|
||||
|
||||
P.e.:
|
||||
RoadRunnerFiles/
|
||||
├── AwesomeMap01
|
||||
│ ├── Asphalt1_Diff.png
|
||||
│ ├── Asphalt1_Norm.png
|
||||
│ ├── Asphalt1_Spec.png
|
||||
│ ├── Grass1_Diff.png
|
||||
│ ├── Grass1_Norm.png
|
||||
│ ├── Grass1_Spec.png
|
||||
│ ├── LaneMarking1_Diff.png
|
||||
│ ├── LaneMarking1_Norm.png
|
||||
│ ├── LaneMarking1_Spec.png
|
||||
│ ├── AwesomeMap01.fbx
|
||||
│ └── AwesomeMap01.xodr
|
||||
└── AwesomeMap02
|
||||
├── Asphalt1_Diff.png
|
||||
├── Asphalt1_Norm.png
|
||||
├── Asphalt1_Spec.png
|
||||
├── Concrete1_Diff.png
|
||||
├── Concrete1_Norm.png
|
||||
├── Concrete1_Spec.png
|
||||
├── Grass1_Diff.png
|
||||
├── Grass1_Norm.png
|
||||
├── Grass1_Spec.png
|
||||
├── LaneMarking1_Diff.png
|
||||
├── LaneMarking1_Norm.png
|
||||
├── LaneMarking1_Spec.png
|
||||
├── AwesomeMap02.fbx
|
||||
└── AwesomeMap02.xodr
|
||||
|
|
@ -39,7 +39,8 @@ void UActorDispatcher::Bind(ACarlaActorFactory &ActorFactory)
|
|||
|
||||
TPair<EActorSpawnResultStatus, FActorView> UActorDispatcher::SpawnActor(
|
||||
const FTransform &Transform,
|
||||
FActorDescription Description)
|
||||
FActorDescription Description,
|
||||
FActorView::IdType DesiredId)
|
||||
{
|
||||
if ((Description.UId == 0u) || (Description.UId > static_cast<uint32>(SpawnFunctions.Num())))
|
||||
{
|
||||
|
@ -59,7 +60,7 @@ TPair<EActorSpawnResultStatus, FActorView> UActorDispatcher::SpawnActor(
|
|||
Result.Status = EActorSpawnResultStatus::UnknownError;
|
||||
}
|
||||
|
||||
auto View = Result.IsValid() ? RegisterActor(*Result.Actor, std::move(Description)) : FActorView();
|
||||
auto View = Result.IsValid() ? RegisterActor(*Result.Actor, std::move(Description), DesiredId) : FActorView();
|
||||
|
||||
if (!View.IsValid())
|
||||
{
|
||||
|
@ -108,9 +109,9 @@ bool UActorDispatcher::DestroyActor(AActor *Actor)
|
|||
return false;
|
||||
}
|
||||
|
||||
FActorView UActorDispatcher::RegisterActor(AActor &Actor, FActorDescription Description)
|
||||
FActorView UActorDispatcher::RegisterActor(AActor &Actor, FActorDescription Description, FActorRegistry::IdType DesiredId)
|
||||
{
|
||||
auto View = Registry.Register(Actor, std::move(Description));
|
||||
auto View = Registry.Register(Actor, std::move(Description), DesiredId);
|
||||
if (View.IsValid())
|
||||
{
|
||||
Actor.OnDestroyed.AddDynamic(this, &UActorDispatcher::OnActorDestroyed);
|
||||
|
|
|
@ -48,7 +48,8 @@ public:
|
|||
/// view is invalid.
|
||||
TPair<EActorSpawnResultStatus, FActorView> SpawnActor(
|
||||
const FTransform &Transform,
|
||||
FActorDescription ActorDescription);
|
||||
FActorDescription ActorDescription,
|
||||
FActorView::IdType DesiredId = 0);
|
||||
|
||||
/// Destroys an actor, properly removing it from the registry.
|
||||
///
|
||||
|
@ -58,7 +59,7 @@ public:
|
|||
|
||||
/// Register an actor that was not created using "SpawnActor" function but
|
||||
/// that should be kept in the registry.
|
||||
FActorView RegisterActor(AActor &Actor, FActorDescription ActorDescription);
|
||||
FActorView RegisterActor(AActor &Actor, FActorDescription ActorDescription, FActorRegistry::IdType DesiredId = 0);
|
||||
|
||||
const TArray<FActorDefinition> &GetActorDefinitions() const
|
||||
{
|
||||
|
@ -85,4 +86,5 @@ private:
|
|||
TArray<TSubclassOf<AActor>> Classes;
|
||||
|
||||
FActorRegistry Registry;
|
||||
|
||||
};
|
||||
|
|
|
@ -50,10 +50,19 @@ static FString GetRelevantTagAsString(const TSet<ECityObjectLabel> &SemanticTags
|
|||
return TEXT("unknown");
|
||||
}
|
||||
|
||||
FActorView FActorRegistry::Register(AActor &Actor, FActorDescription Description)
|
||||
FActorView FActorRegistry::Register(AActor &Actor, FActorDescription Description, IdType DesiredId)
|
||||
{
|
||||
static IdType ID_COUNTER = 0u;
|
||||
const auto Id = ++ID_COUNTER;
|
||||
auto Id = ++ID_COUNTER;
|
||||
|
||||
if (DesiredId != 0 && Id != DesiredId) {
|
||||
// check if the desired Id is free, then use it instead
|
||||
if (!Actors.Contains(DesiredId))
|
||||
Id = DesiredId;
|
||||
if (ID_COUNTER < Id)
|
||||
ID_COUNTER = Id;
|
||||
}
|
||||
|
||||
Actors.Emplace(Id, &Actor);
|
||||
if (Ids.Contains(&Actor))
|
||||
{
|
||||
|
|
|
@ -37,7 +37,7 @@ public:
|
|||
/// actor.
|
||||
///
|
||||
/// @warning Undefined if an actor is registered more than once.
|
||||
FActorView Register(AActor &Actor, FActorDescription Description);
|
||||
FActorView Register(AActor &Actor, FActorDescription Description, IdType DesiredId = 0);
|
||||
|
||||
void Deregister(IdType Id);
|
||||
|
||||
|
|
|
@ -0,0 +1,262 @@
|
|||
// Copyright 1998-2017 Epic Games, Inc. All Rights Reserved.
|
||||
|
||||
|
||||
#include "MapProcessCommandlet.h"
|
||||
#include "GameFramework/WorldSettings.h"
|
||||
#include "UObject/MetaData.h"
|
||||
//#include "CommandletPluginPrivate.h"
|
||||
|
||||
UMapProcessCommandlet::UMapProcessCommandlet()
|
||||
{
|
||||
IsClient = false;
|
||||
IsEditor = false;
|
||||
IsServer = false;
|
||||
LogToConsole = true;
|
||||
#if WITH_EDITORONLY_DATA
|
||||
static ConstructorHelpers::FObjectFinder<UMaterial> MarkingNode(TEXT(
|
||||
"Material'/Game/Carla/Static/GenericMaterials/LaneMarking/M_MarkingLane_W.M_MarkingLane_W'"));
|
||||
static ConstructorHelpers::FObjectFinder<UMaterial> RoadNode(TEXT(
|
||||
"Material'/Game/Carla/Static/GenericMaterials/Masters/LowComplexity/M_Road1.M_Road1'"));
|
||||
static ConstructorHelpers::FObjectFinder<UMaterial> RoadNodeAux(TEXT(
|
||||
"Material'/Game/Carla/Static/GenericMaterials/LaneMarking/M_MarkingLane_Y.M_MarkingLane_Y'"));
|
||||
static ConstructorHelpers::FObjectFinder<UMaterial> TerrainNodeMaterial(TEXT(
|
||||
"Material'/Game/Carla/Static/GenericMaterials/Grass/M_Grass01.M_Grass01'"));
|
||||
|
||||
MarkingNodeMaterial = (UMaterial *) MarkingNode.Object;
|
||||
RoadNodeMaterial = (UMaterial *) RoadNode.Object;
|
||||
MarkingNodeMaterialAux = (UMaterial *) RoadNodeAux.Object;
|
||||
#endif
|
||||
}
|
||||
#if WITH_EDITORONLY_DATA
|
||||
|
||||
bool UMapProcessCommandlet::ParseParams(const FString& InParams)
|
||||
{
|
||||
TArray<FString> Tokens;
|
||||
TArray<FString> Params;
|
||||
TMap<FString, FString> ParamVals;
|
||||
|
||||
ParseCommandLine(*InParams, Tokens, Params, ParamVals);
|
||||
|
||||
const bool bEnoughParams = ParamVals.Num() > 1;
|
||||
|
||||
MapName = ParamVals.FindRef(TEXT("mapname"));
|
||||
|
||||
bOverrideMaterials = Params.Contains(TEXT("use-carla-materials"));
|
||||
|
||||
return bEnoughParams;
|
||||
}
|
||||
|
||||
void UMapProcessCommandlet::MoveMeshes(const FString &SrcPath, const TArray<FString> &DestPath)
|
||||
{
|
||||
|
||||
AssetsObjectLibrary = UObjectLibrary::CreateLibrary(UStaticMesh::StaticClass(), false, GIsEditor);
|
||||
AssetsObjectLibrary->AddToRoot();
|
||||
AssetsObjectLibrary->LoadAssetDataFromPath(*SrcPath);
|
||||
AssetsObjectLibrary->LoadAssetsFromAssetData();
|
||||
|
||||
MapContents.Empty();
|
||||
AssetsObjectLibrary->GetAssetDataList(MapContents);
|
||||
|
||||
UStaticMesh *MeshAsset;
|
||||
FString PackagePath;
|
||||
FString ObjectName;
|
||||
|
||||
if (MapContents.Num() > 0)
|
||||
{
|
||||
int ChosenIndex = 0;
|
||||
FString AssetName;
|
||||
FAssetToolsModule &AssetToolsModule = FModuleManager::LoadModuleChecked<FAssetToolsModule>("AssetTools");
|
||||
for (auto MapAsset : MapContents)
|
||||
{
|
||||
MeshAsset = CastChecked<UStaticMesh>(MapAsset.GetAsset());
|
||||
|
||||
ObjectName = MeshAsset->GetName();
|
||||
|
||||
MapAsset.AssetName.ToString(AssetName);
|
||||
|
||||
|
||||
if (SrcPath.Len())
|
||||
{
|
||||
const FString CurrentPackageName = MeshAsset->GetOutermost()->GetName();
|
||||
//UE_LOG(LogCommandletPlugin, Display, TEXT("DANIEL: %s"), *CurrentPackageName);
|
||||
|
||||
// This is a relative operation
|
||||
if (!ensure(CurrentPackageName.StartsWith(SrcPath)))
|
||||
{
|
||||
continue;
|
||||
}
|
||||
|
||||
if (AssetName.Contains("MarkingNode"))
|
||||
{
|
||||
ChosenIndex=MARKINGLINE_INDEX;
|
||||
}
|
||||
else if (AssetName.Contains("RoadNode"))
|
||||
{
|
||||
ChosenIndex=ROAD_INDEX;
|
||||
} else if (AssetName.Contains("Terrain")) {
|
||||
ChosenIndex=TERRAIN_INDEX;
|
||||
}
|
||||
|
||||
const int32 ShortPackageNameLen = FPackageName::GetLongPackageAssetName(CurrentPackageName).Len();
|
||||
const int32 RelativePathLen = CurrentPackageName.Len() - ShortPackageNameLen - SrcPath.Len() - 1; //
|
||||
// -1
|
||||
// to
|
||||
// exclude
|
||||
// the
|
||||
// trailing
|
||||
// "/"
|
||||
const FString RelativeDestPath = CurrentPackageName.Mid(SrcPath.Len(), RelativePathLen);
|
||||
|
||||
PackagePath = DestPath[ChosenIndex] + RelativeDestPath;
|
||||
}
|
||||
else
|
||||
{
|
||||
// Only a DestPath was supplied, use it
|
||||
PackagePath = DestPath[ChosenIndex];
|
||||
}
|
||||
|
||||
|
||||
MeshAsset->AddToRoot();
|
||||
FString NewPackageName = PackagePath + "/" + ObjectName;
|
||||
|
||||
UPackage *AssetPackage = MapAsset.GetPackage();
|
||||
AssetPackage->SetFolderName(*PackagePath);
|
||||
AssetPackage->FullyLoad();
|
||||
AssetPackage->MarkPackageDirty();
|
||||
FAssetRegistryModule::AssetCreated(MeshAsset);
|
||||
|
||||
MeshAsset->MarkPackageDirty();
|
||||
MeshAsset->GetOuter()->MarkPackageDirty();
|
||||
|
||||
FString CompleteFilename = FPackageName::LongPackageNameToFilename(NewPackageName,
|
||||
FPackageName::GetAssetPackageExtension());
|
||||
UPackage::SavePackage(AssetPackage, MeshAsset, EObjectFlags::RF_Public | EObjectFlags::RF_Standalone,
|
||||
*CompleteFilename, GError, nullptr, true, true, SAVE_NoError);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
void UMapProcessCommandlet::LoadWorld(const FString &SrcPath, FAssetData &AssetData)
|
||||
{
|
||||
|
||||
MapObjectLibrary = UObjectLibrary::CreateLibrary(UWorld::StaticClass(), false, GIsEditor);
|
||||
MapObjectLibrary->AddToRoot();
|
||||
MapObjectLibrary->LoadAssetDataFromPath(*SrcPath);
|
||||
MapObjectLibrary->LoadAssetsFromAssetData();
|
||||
MapObjectLibrary->GetAssetDataList(AssetDatas);
|
||||
|
||||
if (AssetDatas.Num() > 0)
|
||||
{
|
||||
AssetData = AssetDatas.Pop();
|
||||
}
|
||||
}
|
||||
|
||||
void UMapProcessCommandlet::AddMeshesToWorld(
|
||||
const TArray<FString> &SrcPath,
|
||||
bool bMaterialWorkaround)
|
||||
{
|
||||
|
||||
AssetsObjectLibrary = UObjectLibrary::CreateLibrary(UStaticMesh::StaticClass(), false, GIsEditor);
|
||||
AssetsObjectLibrary->AddToRoot();
|
||||
AssetsObjectLibrary->LoadAssetDataFromPaths(SrcPath);
|
||||
AssetsObjectLibrary->LoadAssetsFromAssetData();
|
||||
|
||||
const FTransform zeroTransform = FTransform();
|
||||
FVector initialVector = FVector(0, 0, 0);
|
||||
FRotator initialRotator = FRotator(0, 180, 0);
|
||||
FActorSpawnParameters SpawnInfo;
|
||||
|
||||
MapContents.Empty();
|
||||
AssetsObjectLibrary->GetAssetDataList(MapContents);
|
||||
|
||||
UStaticMesh *MeshAsset;
|
||||
AStaticMeshActor *MeshActor;
|
||||
for (auto MapAsset : MapContents)
|
||||
{
|
||||
MeshAsset = CastChecked<UStaticMesh>(MapAsset.GetAsset());
|
||||
MeshActor = World->SpawnActor<AStaticMeshActor>(AStaticMeshActor::StaticClass(),
|
||||
initialVector,
|
||||
initialRotator);
|
||||
MeshActor->GetStaticMeshComponent()->SetStaticMesh(CastChecked<UStaticMesh>(MeshAsset));
|
||||
|
||||
if (bMaterialWorkaround)
|
||||
{
|
||||
FString AssetName;
|
||||
MapAsset.AssetName.ToString(AssetName);
|
||||
if (AssetName.Contains("MarkingNode"))
|
||||
{
|
||||
MeshActor->GetStaticMeshComponent()->SetMaterial(0, MarkingNodeMaterial);
|
||||
MeshActor->GetStaticMeshComponent()->SetMaterial(1, MarkingNodeMaterialAux);
|
||||
}
|
||||
else if (AssetName.Contains("RoadNode"))
|
||||
{
|
||||
MeshActor->GetStaticMeshComponent()->SetMaterial(0, RoadNodeMaterial);
|
||||
} else if (AssetName.Contains("Terrain"))
|
||||
{
|
||||
MeshActor->GetStaticMeshComponent()->SetMaterial(0, TerrainNodeMaterial);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
World->MarkPackageDirty();
|
||||
|
||||
}
|
||||
|
||||
bool UMapProcessCommandlet::SaveWorld(FAssetData &AssetData, FString &DestPath, FString &WorldName)
|
||||
{
|
||||
FString PackageName = DestPath + "/" + WorldName;
|
||||
UPackage *Package = AssetData.GetPackage();
|
||||
Package->SetFolderName(*DestPath);
|
||||
Package->FullyLoad();
|
||||
Package->MarkPackageDirty();
|
||||
FAssetRegistryModule::AssetCreated(World);
|
||||
|
||||
// Renaming stuff for the map
|
||||
World->Rename(*WorldName, World->GetOuter());
|
||||
FAssetRegistryModule::AssetRenamed(World, *PackageName);
|
||||
World->MarkPackageDirty();
|
||||
World->GetOuter()->MarkPackageDirty();
|
||||
|
||||
// Filling the map stuff
|
||||
AOpenDriveActor *OpenWorldActor =
|
||||
CastChecked<AOpenDriveActor>(World->SpawnActor(AOpenDriveActor::StaticClass(), new FVector(), NULL));
|
||||
OpenWorldActor->BuildRoutes(WorldName);
|
||||
OpenWorldActor->AddSpawners();
|
||||
|
||||
// Saving the package
|
||||
FString PackageFileName = FPackageName::LongPackageNameToFilename(PackageName,
|
||||
FPackageName::GetMapPackageExtension());
|
||||
return UPackage::SavePackage(Package, World, EObjectFlags::RF_Public | EObjectFlags::RF_Standalone,
|
||||
*PackageFileName, GError, nullptr, true, true, SAVE_NoError);
|
||||
}
|
||||
|
||||
int32 UMapProcessCommandlet::Main(const FString &Params)
|
||||
{
|
||||
ParseParams(Params);
|
||||
FString SrcPath = TEXT("/Game/Carla/Static/Imported/") + MapName;
|
||||
FString BaseMap = TEXT("/Game/Carla/Maps/BaseMap");
|
||||
FString WorldDestPath = TEXT("/Game/Carla/ExportedMaps");
|
||||
|
||||
FString RoadsPath = TEXT("/Game/Carla/Static/Road/") + MapName;
|
||||
FString MarkingLinePath = TEXT("/Game/Carla/Static/RoadLines/") + MapName;
|
||||
FString TerrainPath = TEXT("/Game/Carla/Static/Terrain/") + MapName;
|
||||
|
||||
|
||||
|
||||
TArray<FString> DataPath;
|
||||
DataPath.Add(RoadsPath);
|
||||
DataPath.Add(MarkingLinePath);
|
||||
DataPath.Add(TerrainPath);
|
||||
|
||||
FAssetData AssetData;
|
||||
MoveMeshes(SrcPath, DataPath);
|
||||
LoadWorld(*BaseMap, AssetData);
|
||||
World = CastChecked<UWorld>(AssetData.GetAsset());
|
||||
AddMeshesToWorld(DataPath, bOverrideMaterials);
|
||||
SaveWorld(AssetData, WorldDestPath, MapName);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -0,0 +1,135 @@
|
|||
// Copyright 1998-2017 Epic Games, Inc. All Rights Reserved.
|
||||
#pragma once
|
||||
|
||||
#include "Commandlets/Commandlet.h"
|
||||
#include <Engine/World.h>
|
||||
#include <UObject/Package.h>
|
||||
#include <Misc/PackageName.h>
|
||||
#include "CoreMinimal.h"
|
||||
#include <Runtime/Engine/Classes/Engine/ObjectLibrary.h>
|
||||
#include <OpenDriveActor.h>
|
||||
#if WITH_EDITORONLY_DATA
|
||||
#include <Developer/AssetTools/Public/IAssetTools.h>
|
||||
#include <Developer/AssetTools/Public/AssetToolsModule.h>
|
||||
#include <AssetRegistry/Public/AssetRegistryModule.h>
|
||||
#endif //WITH_EDITORONLY_DATA
|
||||
#include <Runtime/Engine/Classes/Engine/StaticMeshActor.h>
|
||||
#include "MapProcessCommandlet.generated.h"
|
||||
|
||||
UCLASS()
|
||||
class UMapProcessCommandlet
|
||||
: public UCommandlet
|
||||
{
|
||||
GENERATED_BODY()
|
||||
|
||||
public:
|
||||
/** Default constructor. */
|
||||
UMapProcessCommandlet();
|
||||
#if WITH_EDITORONLY_DATA
|
||||
|
||||
/**
|
||||
* Parses the command line parameters
|
||||
* @param InParams - The parameters to parse
|
||||
*/
|
||||
bool ParseParams(const FString& InParams);
|
||||
|
||||
/**
|
||||
* Move meshes from one folder to another. It only works with StaticMeshes
|
||||
* @param SrcPath - Source folder from which the StaticMeshes will be obtained
|
||||
* @param DestPath - Posible folder in which the Meshes will be ordered following
|
||||
* the semantic segmentation. It follows ROAD_INDEX, MARKINGLINE_INDEX, TERRAIN_INDEX
|
||||
* for the position in which each path will be stored.
|
||||
*/
|
||||
void MoveMeshes(const FString &SrcPath, const TArray<FString> &DestPath);
|
||||
|
||||
/**
|
||||
* Loads a UWorld object from a given path into a asset data structure.
|
||||
* @param SrcPath - Folder in which the world is located.
|
||||
* @param AssetData - Structure in which the loaded UWorld will be saved.
|
||||
*/
|
||||
void LoadWorld(const FString &SrcPath, FAssetData& AssetData);
|
||||
|
||||
/**
|
||||
* Add StaticMeshes from a folder into the World loaded as UPROPERTY.
|
||||
* @param SrcPath - Array containing the folders from which the Assets will be loaded
|
||||
* @param bMaterialWorkaround - Flag that will trigger a change in the materials to fix a known bug
|
||||
* in RoadRunner.
|
||||
*/
|
||||
void AddMeshesToWorld(const TArray<FString> &SrcPath, bool bMaterialWorkaround);
|
||||
|
||||
/**
|
||||
* Save a given Asset containing a World into a given path with a given name.
|
||||
* @param AssetData - Contains all the info about the World to be saved
|
||||
* @param DestPath - Path in which the asset will be saved.
|
||||
* @param WorldName - Name for the saved world.
|
||||
*/
|
||||
bool SaveWorld(FAssetData& AssetData, FString &DestPath, FString &WorldName);
|
||||
|
||||
public:
|
||||
|
||||
/**
|
||||
* Main method and entry of the commandlet
|
||||
* @param Params - Parameters of the commandlet.
|
||||
*/
|
||||
virtual int32 Main(const FString &Params) override;
|
||||
|
||||
#endif //WITH_EDITORONLY_DATA
|
||||
private:
|
||||
|
||||
|
||||
/** Materials for the workaround */
|
||||
/**
|
||||
* Workaround material for MarkingNodes mesh
|
||||
*/
|
||||
UMaterial* MarkingNodeMaterial;
|
||||
|
||||
/**
|
||||
* Workaround material for the RoadNode mesh
|
||||
*/
|
||||
UMaterial* RoadNodeMaterial;
|
||||
|
||||
/**
|
||||
* Workaround material for the second material for the MarkingNodes
|
||||
*/
|
||||
UMaterial* MarkingNodeMaterialAux;
|
||||
|
||||
/**
|
||||
* Workaround material for the TerrainNodes
|
||||
*/
|
||||
UMaterial* TerrainNodeMaterial;
|
||||
|
||||
/**
|
||||
* Index in which everything related to the road will be stored in inclass arrays
|
||||
*/
|
||||
static const int ROAD_INDEX = 0;
|
||||
/**
|
||||
* Index in which everything related to the marking lines will be stored in inclass arrays
|
||||
*/
|
||||
static const int MARKINGLINE_INDEX = 1;
|
||||
/**
|
||||
* Index in which everything related to the terrain will be stored in inclass arrays
|
||||
*/
|
||||
static const int TERRAIN_INDEX = 2;
|
||||
|
||||
UPROPERTY()
|
||||
bool bOverrideMaterials;
|
||||
|
||||
//UProperties are necesary or else the GC will eat everything up
|
||||
UPROPERTY()
|
||||
FString MapName;
|
||||
|
||||
UPROPERTY()
|
||||
UObjectLibrary* MapObjectLibrary;
|
||||
|
||||
UPROPERTY()
|
||||
TArray<FAssetData> AssetDatas;
|
||||
|
||||
UPROPERTY()
|
||||
UWorld* World;
|
||||
|
||||
UPROPERTY()
|
||||
UObjectLibrary* AssetsObjectLibrary;
|
||||
|
||||
UPROPERTY()
|
||||
TArray<FAssetData> MapContents;
|
||||
};
|
|
@ -18,7 +18,8 @@
|
|||
static FString UCarlaEpisode_GetTrafficSignId(ETrafficSignState State)
|
||||
{
|
||||
using TSS = ETrafficSignState;
|
||||
switch (State) {
|
||||
switch (State)
|
||||
{
|
||||
case TSS::TrafficLightRed:
|
||||
case TSS::TrafficLightYellow:
|
||||
case TSS::TrafficLightGreen: return TEXT("traffic.traffic_light");
|
||||
|
@ -39,16 +40,17 @@ static FString UCarlaEpisode_GetTrafficSignId(ETrafficSignState State)
|
|||
UCarlaEpisode::UCarlaEpisode(const FObjectInitializer &ObjectInitializer)
|
||||
: Super(ObjectInitializer),
|
||||
Id([]() {
|
||||
static uint32 COUNTER = 0u;
|
||||
return ++COUNTER;
|
||||
}()) {
|
||||
static uint32 COUNTER = 0u;
|
||||
return ++COUNTER;
|
||||
} ()) {
|
||||
ActorDispatcher = CreateDefaultSubobject<UActorDispatcher>(TEXT("ActorDispatcher"));
|
||||
}
|
||||
|
||||
TArray<FTransform> UCarlaEpisode::GetRecommendedSpawnPoints() const
|
||||
{
|
||||
TArray<FTransform> SpawnPoints;
|
||||
for (TActorIterator<AVehicleSpawnPoint> It(GetWorld()); It; ++It) {
|
||||
for (TActorIterator<AVehicleSpawnPoint> It(GetWorld()); It; ++It)
|
||||
{
|
||||
SpawnPoints.Add(It->GetActorTransform());
|
||||
}
|
||||
return SpawnPoints;
|
||||
|
@ -65,7 +67,9 @@ carla::rpc::Actor UCarlaEpisode::SerializeActor(FActorView ActorView) const
|
|||
{
|
||||
Actor.parent_id = FindActor(Parent).GetActorId();
|
||||
}
|
||||
} else {
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Warning, TEXT("Trying to serialize invalid actor"));
|
||||
}
|
||||
return Actor;
|
||||
|
@ -77,6 +81,17 @@ void UCarlaEpisode::AttachActors(AActor *Child, AActor *Parent)
|
|||
check(Parent != nullptr);
|
||||
Child->AttachToActor(Parent, FAttachmentTransformRules::KeepRelativeTransform);
|
||||
Child->SetOwner(Parent);
|
||||
|
||||
// recorder event
|
||||
if (Recorder->IsEnabled())
|
||||
{
|
||||
CarlaRecorderEventParent RecEvent
|
||||
{
|
||||
FindActor(Child).GetActorId(),
|
||||
FindActor(Parent).GetActorId()
|
||||
};
|
||||
Recorder->AddEvent(std::move(RecEvent));
|
||||
}
|
||||
}
|
||||
|
||||
void UCarlaEpisode::InitializeAtBeginPlay()
|
||||
|
@ -127,3 +142,33 @@ void UCarlaEpisode::InitializeAtBeginPlay()
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
void UCarlaEpisode::EndPlay(void)
|
||||
{
|
||||
// stop recorder and replayer
|
||||
if (Recorder)
|
||||
{
|
||||
Recorder->Stop();
|
||||
if (Recorder->GetReplayer()->IsEnabled())
|
||||
{
|
||||
Recorder->GetReplayer()->Stop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
std::string UCarlaEpisode::StartRecorder(std::string Name)
|
||||
{
|
||||
std::string result;
|
||||
FString Name2(Name.c_str());
|
||||
|
||||
if (Recorder)
|
||||
{
|
||||
result = Recorder->Start(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir()), Name2, MapName);
|
||||
}
|
||||
else
|
||||
{
|
||||
result = "Recorder is not ready";
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
|
|
@ -9,11 +9,14 @@
|
|||
#include "Carla/Actor/ActorDispatcher.h"
|
||||
#include "Carla/Sensor/WorldObserver.h"
|
||||
#include "Carla/Weather/Weather.h"
|
||||
|
||||
#include "GameFramework/Pawn.h"
|
||||
#include "Carla/Server/TheNewCarlaServer.h"
|
||||
#include "Carla/Recorder/CarlaRecorder.h"
|
||||
|
||||
#include <compiler/disable-ue4-macros.h>
|
||||
#include <carla/rpc/Actor.h>
|
||||
#include <carla/rpc/ActorDescription.h>
|
||||
#include <carla/geom/BoundingBox.h>
|
||||
#include <carla/streaming/Server.h>
|
||||
#include <compiler/enable-ue4-macros.h>
|
||||
|
||||
#include "CarlaEpisode.generated.h"
|
||||
|
@ -141,9 +144,24 @@ public:
|
|||
/// view is invalid.
|
||||
TPair<EActorSpawnResultStatus, FActorView> SpawnActorWithInfo(
|
||||
const FTransform &Transform,
|
||||
FActorDescription ActorDescription)
|
||||
FActorDescription thisActorDescription,
|
||||
FActorView::IdType DesiredId = 0)
|
||||
{
|
||||
return ActorDispatcher->SpawnActor(Transform, std::move(ActorDescription));
|
||||
auto result = ActorDispatcher->SpawnActor(Transform, thisActorDescription, DesiredId);
|
||||
if (Recorder->IsEnabled())
|
||||
{
|
||||
if (result.Key == EActorSpawnResultStatus::Success)
|
||||
{
|
||||
Recorder->CreateRecorderEventAdd(
|
||||
result.Value.GetActorId(),
|
||||
static_cast<uint8_t>(result.Value.GetActorType()),
|
||||
Transform,
|
||||
std::move(thisActorDescription)
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
/// Spawns an actor based on @a ActorDescription at @a Transform. To properly
|
||||
|
@ -170,6 +188,16 @@ public:
|
|||
UFUNCTION(BlueprintCallable)
|
||||
bool DestroyActor(AActor *Actor)
|
||||
{
|
||||
if (Recorder->IsEnabled())
|
||||
{
|
||||
// recorder event
|
||||
CarlaRecorderEventDel RecEvent
|
||||
{
|
||||
GetActorRegistry().Find(Actor).GetActorId()
|
||||
};
|
||||
Recorder->AddEvent(std::move(RecEvent));
|
||||
}
|
||||
|
||||
return ActorDispatcher->DestroyActor(Actor);
|
||||
}
|
||||
|
||||
|
@ -186,17 +214,41 @@ public:
|
|||
// -- Private methods and members --------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
ACarlaRecorder *GetRecorder() const
|
||||
{
|
||||
return Recorder;
|
||||
}
|
||||
|
||||
void SetRecorder(ACarlaRecorder *Rec)
|
||||
{
|
||||
Recorder = Rec;
|
||||
}
|
||||
|
||||
CarlaReplayer *GetReplayer() const
|
||||
{
|
||||
return Recorder->GetReplayer();
|
||||
}
|
||||
|
||||
std::string StartRecorder(std::string name);
|
||||
|
||||
private:
|
||||
|
||||
friend class ATheNewCarlaGameModeBase;
|
||||
|
||||
void InitializeAtBeginPlay();
|
||||
void EndPlay();
|
||||
|
||||
void RegisterActorFactory(ACarlaActorFactory &ActorFactory)
|
||||
{
|
||||
ActorDispatcher->Bind(ActorFactory);
|
||||
}
|
||||
|
||||
std::pair<int, FActorView&> TryToCreateReplayerActor(
|
||||
FVector &Location,
|
||||
FVector &Rotation,
|
||||
FActorDescription &ActorDesc,
|
||||
unsigned int desiredId);
|
||||
|
||||
const uint32 Id = 0u;
|
||||
|
||||
UPROPERTY(VisibleAnywhere)
|
||||
|
@ -213,4 +265,6 @@ private:
|
|||
|
||||
UPROPERTY(VisibleAnywhere)
|
||||
AWorldObserver *WorldObserver = nullptr;
|
||||
|
||||
ACarlaRecorder *Recorder = nullptr;
|
||||
};
|
||||
|
|
|
@ -16,6 +16,8 @@ ATheNewCarlaGameModeBase::ATheNewCarlaGameModeBase(const FObjectInitializer& Obj
|
|||
|
||||
Episode = CreateDefaultSubobject<UCarlaEpisode>(TEXT("Episode"));
|
||||
|
||||
Recorder = CreateDefaultSubobject<ACarlaRecorder>(TEXT("Recorder"));
|
||||
|
||||
TaggerDelegate = CreateDefaultSubobject<UTaggerDelegate>(TEXT("TaggerDelegate"));
|
||||
CarlaSettingsDelegate = CreateDefaultSubobject<UCarlaSettingsDelegate>(TEXT("CarlaSettingsDelegate"));
|
||||
}
|
||||
|
@ -82,6 +84,10 @@ void ATheNewCarlaGameModeBase::InitGame(
|
|||
Episode->WorldObserver->SetStream(GameInstance->GetServer().OpenMultiStream());
|
||||
|
||||
SpawnActorFactories();
|
||||
|
||||
// make connection between Episode and Recorder
|
||||
Recorder->SetEpisode(Episode);
|
||||
Episode->SetRecorder(Recorder);
|
||||
}
|
||||
|
||||
void ATheNewCarlaGameModeBase::RestartPlayer(AController *NewPlayer)
|
||||
|
@ -113,10 +119,12 @@ void ATheNewCarlaGameModeBase::Tick(float DeltaSeconds)
|
|||
Super::Tick(DeltaSeconds);
|
||||
|
||||
GameInstance->Tick(DeltaSeconds);
|
||||
if (Recorder) Recorder->Tick(DeltaSeconds);
|
||||
}
|
||||
|
||||
void ATheNewCarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||
{
|
||||
Episode->EndPlay();
|
||||
GameInstance->NotifyEndEpisode();
|
||||
|
||||
Super::EndPlay(EndPlayReason);
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include "Carla/Actor/CarlaActorFactory.h"
|
||||
#include "Carla/Game/CarlaEpisode.h"
|
||||
#include "Carla/Game/CarlaGameInstance.h"
|
||||
#include "Carla/Recorder/CarlaRecorder.h"
|
||||
#include "Carla/Game/TaggerDelegate.h"
|
||||
#include "Carla/Settings/CarlaSettingsDelegate.h"
|
||||
#include "Carla/Weather/Weather.h"
|
||||
|
@ -62,6 +63,9 @@ private:
|
|||
UPROPERTY()
|
||||
UCarlaEpisode *Episode = nullptr;
|
||||
|
||||
UPROPERTY()
|
||||
ACarlaRecorder *Recorder = nullptr;
|
||||
|
||||
/// The class of Weather to spawn.
|
||||
UPROPERTY(Category = "CARLA Game Mode", EditAnywhere)
|
||||
TSubclassOf<AWeather> WeatherClass;
|
||||
|
|
|
@ -37,6 +37,35 @@ AOpenDriveActor::AOpenDriveActor(const FObjectInitializer &ObjectInitializer)
|
|||
: Super(ObjectInitializer)
|
||||
{
|
||||
PrimaryActorTick.bCanEverTick = false;
|
||||
#if WITH_EDITORONLY_DATA
|
||||
static ConstructorHelpers::FObjectFinder<UBlueprint> TrafficLightBP(TEXT(
|
||||
"Blueprint'/Game/Carla/Static/TrafficSigns/Streetlights_01/BP_TrafficLightPole.BP_TrafficLightPole'"));
|
||||
TrafficLightBlueprintClass = (UClass *) TrafficLightBP.Object->GeneratedClass;
|
||||
|
||||
static ConstructorHelpers::FObjectFinder<UBlueprint> TrafficGroupBP(TEXT(
|
||||
"Blueprint'/Game/Carla/Static/TrafficSigns/Streetlights_01/BP_TrafficLightPoleGroup.BP_TrafficLightPoleGroup'"));
|
||||
TrafficGroupBlueprintClass = (UClass *) TrafficGroupBP.Object->GeneratedClass;
|
||||
|
||||
static ConstructorHelpers::FObjectFinder<UBlueprint> TrafficSign30BP(TEXT(
|
||||
"Blueprint'/Game/Carla/Static/TrafficSigns/PostSigns/Round/SpeedLimiters/BP_SpeedLimit30.BP_SpeedLimit30'"));
|
||||
TrafficSign30BlueprintClass = (UClass *) TrafficSign30BP.Object->GeneratedClass;
|
||||
|
||||
/*static ConstructorHelpers::FObjectFinder<UBlueprint> TrafficSign40BP(TEXT(
|
||||
"Blueprint'/Game/Carla/Static/TrafficSigns/PostSigns/Round/SpeedLimiters/BP_SpeedLimit40.BP_SpeedLimit40'"));
|
||||
TrafficSign40BlueprintClass = (UClass *) TrafficSign40BP.Object->GeneratedClass;*/
|
||||
|
||||
static ConstructorHelpers::FObjectFinder<UBlueprint> TrafficSign60BP(TEXT(
|
||||
"Blueprint'/Game/Carla/Static/TrafficSigns/PostSigns/Round/SpeedLimiters/BP_SpeedLimit60.BP_SpeedLimit60'"));
|
||||
TrafficSign60BlueprintClass = (UClass *) TrafficSign60BP.Object->GeneratedClass;
|
||||
|
||||
static ConstructorHelpers::FObjectFinder<UBlueprint> TrafficSign90BP(TEXT(
|
||||
"Blueprint'/Game/Carla/Static/TrafficSigns/PostSigns/Round/SpeedLimiters/BP_SpeedLimit90.BP_SpeedLimit90'"));
|
||||
TrafficSign90BlueprintClass = (UClass *) TrafficSign90BP.Object->GeneratedClass;
|
||||
|
||||
static ConstructorHelpers::FObjectFinder<UBlueprint> TrafficSign100BP(TEXT(
|
||||
"Blueprint'/Game/Carla/Static/TrafficSigns/PostSigns/Round/SpeedLimiters/BP_SpeedLimit100.BP_SpeedLimit100'"));
|
||||
TrafficSign100BlueprintClass = (UClass *) TrafficSign100BP.Object->GeneratedClass;
|
||||
#endif // WITH_EDITORONLY_DATA
|
||||
|
||||
// Structure to hold one-time initialization
|
||||
static struct FConstructorStatics
|
||||
|
@ -140,17 +169,26 @@ void AOpenDriveActor::PostEditChangeProperty(struct FPropertyChangedEvent &Event
|
|||
#endif // WITH_EDITOR
|
||||
|
||||
void AOpenDriveActor::BuildRoutes()
|
||||
{
|
||||
BuildRoutes(GetWorld()->GetMapName());
|
||||
}
|
||||
|
||||
void AOpenDriveActor::BuildRoutes(FString MapName)
|
||||
{
|
||||
using CarlaMath = carla::geom::Math;
|
||||
using IdType = carla::road::element::id_type;
|
||||
using Waypoint = carla::road::element::Waypoint;
|
||||
using WaypointGen = carla::road::WaypointGenerator;
|
||||
using TrafficGroup = carla::opendrive::types::TrafficLightGroup;
|
||||
using TrafficLight = carla::opendrive::types::TrafficLight;
|
||||
using TrafficBoxComponent = carla::opendrive::types::BoxComponent;
|
||||
using TrafficSign = carla::opendrive::types::TrafficSign;
|
||||
|
||||
std::string ParseError;
|
||||
|
||||
// As the OpenDrive file has the same name as level, build the path to the
|
||||
// xodr file using the lavel name and the game content directory.
|
||||
const FString XodrContent = FOpenDrive::Load(GetWorld()->GetMapName());
|
||||
const FString XodrContent = FOpenDrive::Load(MapName);
|
||||
|
||||
auto map_ptr = carla::opendrive::OpenDrive::Load(
|
||||
TCHAR_TO_UTF8(*XodrContent),
|
||||
|
@ -191,7 +229,8 @@ void AOpenDriveActor::BuildRoutes()
|
|||
// Create an identifier of the current lane
|
||||
const auto Identifier = std::make_pair(RoadId, LaneId);
|
||||
|
||||
// If Identifier does not exist in AlreadyVisited we haven't visited the lane
|
||||
// If Identifier does not exist in AlreadyVisited we haven't visited the
|
||||
// lane
|
||||
if (!std::any_of(AlreadyVisited.begin(), AlreadyVisited.end(), [&Identifier](auto i) {
|
||||
return (i.first == Identifier.first && i.second == Identifier.second);
|
||||
}))
|
||||
|
@ -240,6 +279,119 @@ void AOpenDriveActor::BuildRoutes()
|
|||
}
|
||||
}
|
||||
}
|
||||
|
||||
const std::vector<TrafficGroup> TrafficLightGroup = map.GetTrafficGroups();
|
||||
for (TrafficGroup CurrentTrafficLightGroup : TrafficLightGroup)
|
||||
{
|
||||
double RedTime = CurrentTrafficLightGroup.red_time;
|
||||
double YellowTime = CurrentTrafficLightGroup.yellow_time;
|
||||
double GreenTime = CurrentTrafficLightGroup.green_time;
|
||||
FActorSpawnParameters SpawnParams;
|
||||
FOutputDeviceNull ar;
|
||||
AActor *SpawnedTrafficGroup = GetWorld()->SpawnActor<AActor>(TrafficGroupBlueprintClass,
|
||||
FVector(0, 0, 0),
|
||||
FRotator(0, 0, 0),
|
||||
SpawnParams);
|
||||
FString SetTrafficTimesCommand = FString::Printf(TEXT("SetTrafficTimes %f %f %f"),
|
||||
RedTime, YellowTime, GreenTime);
|
||||
SpawnedTrafficGroup->CallFunctionByNameWithArguments(*SetTrafficTimesCommand, ar, NULL, true);
|
||||
for (TrafficLight CurrentTrafficLight : CurrentTrafficLightGroup.traffic_lights)
|
||||
{
|
||||
FVector TLPos =
|
||||
FVector(CurrentTrafficLight.x_pos, CurrentTrafficLight.y_pos, CurrentTrafficLight.z_pos);
|
||||
FRotator TLRot = FRotator(CurrentTrafficLight.x_rot,
|
||||
CurrentTrafficLight.z_rot,
|
||||
CurrentTrafficLight.y_rot);
|
||||
AActor *SpawnedTrafficLight = GetWorld()->SpawnActor<AActor>(TrafficLightBlueprintClass,
|
||||
TLPos,
|
||||
TLRot,
|
||||
SpawnParams);
|
||||
FString AddTrafficLightCommand = FString::Printf(TEXT("AddTrafficLightPole %s"),
|
||||
*SpawnedTrafficLight->GetName());
|
||||
SpawnedTrafficGroup->CallFunctionByNameWithArguments(*AddTrafficLightCommand, ar, NULL, true);
|
||||
PersistentTrafficLights.Push(SpawnedTrafficGroup);
|
||||
SpawnedTrafficLight->CallFunctionByNameWithArguments(TEXT("InitData"), ar, NULL, true);
|
||||
for (TrafficBoxComponent TfBoxComponent : CurrentTrafficLight.box_areas)
|
||||
{
|
||||
FVector TLBoxPos = FVector(TfBoxComponent.x_pos,
|
||||
TfBoxComponent.y_pos,
|
||||
TfBoxComponent.z_pos);
|
||||
FRotator TLBoxRot = FRotator(TfBoxComponent.x_rot,
|
||||
TfBoxComponent.z_rot,
|
||||
TfBoxComponent.y_rot);
|
||||
|
||||
FString BoxCommand = FString::Printf(TEXT("SetBoxLocationAndRotation %f %f %f %f %f %f"),
|
||||
TLBoxPos.X,
|
||||
TLBoxPos.Y,
|
||||
TLBoxPos.Z,
|
||||
TLBoxRot.Pitch,
|
||||
TLBoxRot.Roll,
|
||||
TLBoxRot.Yaw);
|
||||
SpawnedTrafficLight->CallFunctionByNameWithArguments(*BoxCommand, ar, NULL, true);
|
||||
PersistentTrafficLights.Push(SpawnedTrafficLight);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
const std::vector<TrafficSign> TrafficSigns = map.GetTrafficSigns();
|
||||
for (TrafficSign CurrentTrafficSign : TrafficSigns) {
|
||||
//switch()
|
||||
AActor* SignActor;
|
||||
FOutputDeviceNull ar;
|
||||
|
||||
FVector TSLoc = FVector(CurrentTrafficSign.x_pos, CurrentTrafficSign.y_pos, CurrentTrafficSign.z_pos);
|
||||
FRotator TSRot = FRotator(CurrentTrafficSign.x_rot, CurrentTrafficSign.z_rot, CurrentTrafficSign.y_rot);
|
||||
FActorSpawnParameters SpawnParams;
|
||||
switch(CurrentTrafficSign.speed) {
|
||||
case 30:
|
||||
SignActor = GetWorld()->SpawnActor<AActor>(TrafficSign30BlueprintClass,
|
||||
TSLoc,
|
||||
TSRot,
|
||||
SpawnParams);
|
||||
break;
|
||||
case 60:
|
||||
SignActor = GetWorld()->SpawnActor<AActor>(TrafficSign60BlueprintClass,
|
||||
TSLoc,
|
||||
TSRot,
|
||||
SpawnParams);
|
||||
break;
|
||||
case 90:
|
||||
SignActor = GetWorld()->SpawnActor<AActor>(TrafficSign90BlueprintClass,
|
||||
TSLoc,
|
||||
TSRot,
|
||||
SpawnParams);
|
||||
break;
|
||||
case 100:
|
||||
SignActor = GetWorld()->SpawnActor<AActor>(TrafficSign100BlueprintClass,
|
||||
TSLoc,
|
||||
TSRot,
|
||||
SpawnParams);
|
||||
break;
|
||||
default:
|
||||
FString errorMessage = "Traffic Sign not found. Posibilities: 30, 60, 90, 100";
|
||||
UE_LOG(LogCarla, Warning, TEXT("%s"), *errorMessage);
|
||||
break;
|
||||
}
|
||||
PersistentTrafficSigns.Push(SignActor);
|
||||
for (TrafficBoxComponent TfBoxComponent : CurrentTrafficSign.box_areas)
|
||||
{
|
||||
FVector TLBoxPos = FVector(TfBoxComponent.x_pos,
|
||||
TfBoxComponent.y_pos,
|
||||
TfBoxComponent.z_pos);
|
||||
FRotator TLBoxRot = FRotator(TfBoxComponent.x_rot,
|
||||
TfBoxComponent.z_rot,
|
||||
TfBoxComponent.y_rot);
|
||||
|
||||
FString BoxCommand = FString::Printf(TEXT("SetBoxLocationAndRotation %f %f %f %f %f %f"),
|
||||
TLBoxPos.X,
|
||||
TLBoxPos.Y,
|
||||
TLBoxPos.Z,
|
||||
TLBoxRot.Pitch,
|
||||
TLBoxRot.Roll,
|
||||
TLBoxRot.Yaw);
|
||||
SignActor->CallFunctionByNameWithArguments(*BoxCommand, ar, NULL, true);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void AOpenDriveActor::RemoveRoutes()
|
||||
|
@ -253,6 +405,22 @@ void AOpenDriveActor::RemoveRoutes()
|
|||
}
|
||||
}
|
||||
RoutePlanners.Empty();
|
||||
const int tl_num = PersistentTrafficLights.Num();
|
||||
for (int i = 0; i < tl_num; i++)
|
||||
{
|
||||
if(PersistentTrafficLights[i] != nullptr) {
|
||||
PersistentTrafficLights[i]->Destroy();
|
||||
}
|
||||
}
|
||||
PersistentTrafficLights.Empty();
|
||||
const int ts_num = PersistentTrafficSigns.Num();
|
||||
for (int i = 0; i < ts_num; i++)
|
||||
{
|
||||
if(PersistentTrafficSigns[i] != nullptr) {
|
||||
PersistentTrafficSigns[i]->Destroy();
|
||||
}
|
||||
}
|
||||
PersistentTrafficSigns.Empty();
|
||||
}
|
||||
|
||||
void AOpenDriveActor::DebugRoutes() const
|
||||
|
|
|
@ -16,6 +16,8 @@
|
|||
|
||||
#include "Vehicle/VehicleSpawnPoint.h"
|
||||
|
||||
#include "Runtime/Core/Public/Misc/OutputDeviceNull.h"
|
||||
|
||||
#include <compiler/disable-ue4-macros.h>
|
||||
#include <carla/opendrive/OpenDrive.h>
|
||||
#include <compiler/enable-ue4-macros.h>
|
||||
|
@ -43,6 +45,33 @@ private:
|
|||
UPROPERTY()
|
||||
TArray<AVehicleSpawnPoint *> VehicleSpawners;
|
||||
|
||||
UPROPERTY()
|
||||
TArray<AActor *> PersistentTrafficLights;
|
||||
|
||||
UPROPERTY()
|
||||
TArray<AActor *> PersistentTrafficSigns;
|
||||
|
||||
UPROPERTY()
|
||||
TSubclassOf<class AActor> TrafficLightBlueprintClass;
|
||||
|
||||
UPROPERTY()
|
||||
TSubclassOf<class AActor> TrafficGroupBlueprintClass;
|
||||
|
||||
UPROPERTY()
|
||||
TSubclassOf<class AActor> TrafficSign30BlueprintClass;
|
||||
|
||||
UPROPERTY()
|
||||
TSubclassOf<class AActor> TrafficSign40BlueprintClass;
|
||||
|
||||
UPROPERTY()
|
||||
TSubclassOf<class AActor> TrafficSign60BlueprintClass;
|
||||
|
||||
UPROPERTY()
|
||||
TSubclassOf<class AActor> TrafficSign90BlueprintClass;
|
||||
|
||||
UPROPERTY()
|
||||
TSubclassOf<class AActor> TrafficSign100BlueprintClass;
|
||||
|
||||
#if WITH_EDITORONLY_DATA
|
||||
/// Generate the road network using an OpenDrive file (named as the current
|
||||
/// .umap)
|
||||
|
@ -96,6 +125,8 @@ public:
|
|||
|
||||
void BuildRoutes();
|
||||
|
||||
void BuildRoutes(FString MapName);
|
||||
|
||||
/// Remove all the existing ARoutePlanner and VehicleSpawners previously
|
||||
/// generated by this class to avoid overlapping
|
||||
void RemoveRoutes();
|
||||
|
|
|
@ -0,0 +1,330 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
// #include "Carla.h"
|
||||
#include "CarlaRecorder.h"
|
||||
#include "Carla/Actor/ActorDescription.h"
|
||||
|
||||
#include <ctime>
|
||||
#include <sstream>
|
||||
|
||||
ACarlaRecorder::ACarlaRecorder(void)
|
||||
{
|
||||
PrimaryActorTick.TickGroup = TG_PrePhysics;
|
||||
Disable();
|
||||
}
|
||||
|
||||
ACarlaRecorder::ACarlaRecorder(const FObjectInitializer &ObjectInitializer)
|
||||
: Super(ObjectInitializer)
|
||||
{
|
||||
PrimaryActorTick.TickGroup = TG_PrePhysics;
|
||||
Disable();
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ShowFileInfo(std::string Path, std::string Name)
|
||||
{
|
||||
return Query.QueryInfo(Path + Name);
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ShowFileCollisions(std::string Path, std::string Name, char Type1, char Type2)
|
||||
{
|
||||
return Query.QueryCollisions(Path + Name, Type1, Type2);
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ShowFileActorsBlocked(std::string Path, std::string Name, double MinTime, double MinDistance)
|
||||
{
|
||||
return Query.QueryBlocked(Path + Name, MinTime, MinDistance);
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ReplayFile(std::string Path, std::string Name, double TimeStart, double Duration, uint32_t FollowId)
|
||||
{
|
||||
Stop();
|
||||
return Replayer.ReplayFile(Path + Name, TimeStart, Duration, FollowId);
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Tick(float DeltaSeconds)
|
||||
{
|
||||
Super::Tick(DeltaSeconds);
|
||||
|
||||
if (!Episode)
|
||||
return;
|
||||
|
||||
// check if recording
|
||||
if (Enabled)
|
||||
{
|
||||
const FActorRegistry &Registry = Episode->GetActorRegistry();
|
||||
|
||||
// through all actors in registry
|
||||
for (auto It = Registry.begin(); It != Registry.end(); ++It)
|
||||
{
|
||||
FActorView View = *It;
|
||||
AActor *Actor;
|
||||
switch (View.GetActorType())
|
||||
{
|
||||
// save the transform of all vehicles and walkers
|
||||
case FActorView::ActorType::Vehicle:
|
||||
case FActorView::ActorType::Walker:
|
||||
// get position of the vehicle
|
||||
Actor = View.GetActor();
|
||||
check(Actor != nullptr);
|
||||
AddPosition(CarlaRecorderPosition
|
||||
{
|
||||
View.GetActorId(),
|
||||
Actor->GetTransform().GetTranslation(),
|
||||
Actor->GetTransform().GetRotation().Euler()
|
||||
});
|
||||
break;
|
||||
|
||||
// save the state of each traffic light
|
||||
case FActorView::ActorType::TrafficLight:
|
||||
// get states
|
||||
Actor = View.GetActor();
|
||||
check(Actor != nullptr);
|
||||
auto TrafficLight = Cast<ATrafficLightBase>(Actor);
|
||||
if (TrafficLight != nullptr)
|
||||
{
|
||||
AddState(CarlaRecorderStateTrafficLight
|
||||
{
|
||||
View.GetActorId(),
|
||||
TrafficLight->GetTimeIsFrozen(),
|
||||
TrafficLight->GetElapsedTime(),
|
||||
static_cast<char>(TrafficLight->GetTrafficLightState())
|
||||
});
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// write all data for this frame
|
||||
Write(DeltaSeconds);
|
||||
}
|
||||
else if (Episode->GetReplayer()->IsEnabled())
|
||||
{
|
||||
// replayer
|
||||
Episode->GetReplayer()->Tick(DeltaSeconds);
|
||||
}
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Enable(void)
|
||||
{
|
||||
PrimaryActorTick.bCanEverTick = true;
|
||||
Enabled = true;
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Disable(void)
|
||||
{
|
||||
PrimaryActorTick.bCanEverTick = false;
|
||||
Enabled = false;
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::Start(FString Path, FString Name, FString MapName)
|
||||
{
|
||||
// stop replayer if any in course
|
||||
if (Replayer.IsEnabled())
|
||||
Replayer.Stop();
|
||||
|
||||
// stop recording
|
||||
Stop();
|
||||
|
||||
NextCollisionId = 0;
|
||||
FString Filename = Path + Name;
|
||||
|
||||
// binary file
|
||||
// file.open(filename.str(), std::ios::binary | std::ios::trunc |
|
||||
// std::ios::out);
|
||||
File.open(TCHAR_TO_UTF8(*Filename), std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
return "";
|
||||
}
|
||||
|
||||
// save info
|
||||
Info.Version = 1;
|
||||
Info.Magic = TEXT("CARLA_RECORDER");
|
||||
Info.Date = std::time(0);
|
||||
Info.Mapfile = MapName;
|
||||
|
||||
// write general info
|
||||
Info.Write(File);
|
||||
|
||||
Frames.Reset();
|
||||
|
||||
Enable();
|
||||
|
||||
// add all existing actors
|
||||
AddExistingActors();
|
||||
|
||||
return std::string(TCHAR_TO_UTF8(*Filename));
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Stop(void)
|
||||
{
|
||||
Disable();
|
||||
|
||||
if (File)
|
||||
{
|
||||
File.close();
|
||||
}
|
||||
|
||||
Clear();
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Clear(void)
|
||||
{
|
||||
EventsAdd.Clear();
|
||||
EventsDel.Clear();
|
||||
EventsParent.Clear();
|
||||
Collisions.Clear();
|
||||
Positions.Clear();
|
||||
States.Clear();
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Write(double DeltaSeconds)
|
||||
{
|
||||
// update this frame data
|
||||
Frames.SetFrame(DeltaSeconds);
|
||||
|
||||
// start
|
||||
Frames.WriteStart(File);
|
||||
|
||||
// write data
|
||||
EventsAdd.Write(File);
|
||||
EventsDel.Write(File);
|
||||
EventsParent.Write(File);
|
||||
Collisions.Write(File);
|
||||
Positions.Write(File);
|
||||
States.Write(File);
|
||||
|
||||
// end
|
||||
Frames.WriteEnd(File);
|
||||
|
||||
Clear();
|
||||
}
|
||||
|
||||
inline void ACarlaRecorder::AddPosition(const CarlaRecorderPosition &Position)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
Positions.Add(Position);
|
||||
}
|
||||
}
|
||||
|
||||
inline void ACarlaRecorder::AddEvent(const CarlaRecorderEventAdd &Event)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
EventsAdd.Add(std::move(Event));
|
||||
}
|
||||
}
|
||||
inline void ACarlaRecorder::AddEvent(const CarlaRecorderEventDel &Event)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
EventsDel.Add(std::move(Event));
|
||||
}
|
||||
}
|
||||
inline void ACarlaRecorder::AddEvent(const CarlaRecorderEventParent &Event)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
EventsParent.Add(std::move(Event));
|
||||
}
|
||||
}
|
||||
void ACarlaRecorder::AddCollision(AActor *Actor1, AActor *Actor2)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
CarlaRecorderCollision Collision;
|
||||
|
||||
// some inits
|
||||
Collision.Id = NextCollisionId++;
|
||||
Collision.IsActor1Hero = false;
|
||||
Collision.IsActor2Hero = false;
|
||||
|
||||
// check actor 1
|
||||
if (Episode->GetActorRegistry().Find(Actor1).GetActorInfo() != nullptr)
|
||||
{
|
||||
auto *Role = Episode->GetActorRegistry().Find(Actor1).GetActorInfo()->Description.Variations.Find("role_name");
|
||||
if (Role != nullptr)
|
||||
Collision.IsActor1Hero = (Role->Value == "hero");
|
||||
}
|
||||
Collision.DatabaseId1 = Episode->GetActorRegistry().Find(Actor1).GetActorId();
|
||||
|
||||
// check actor 2
|
||||
if (Episode->GetActorRegistry().Find(Actor2).GetActorInfo() != nullptr)
|
||||
{
|
||||
auto Role = Episode->GetActorRegistry().Find(Actor2).GetActorInfo()->Description.Variations.Find("role_name");
|
||||
if (Role != nullptr)
|
||||
Collision.IsActor2Hero = (Role->Value == "hero");
|
||||
}
|
||||
Collision.DatabaseId2 = Episode->GetActorRegistry().Find(Actor2).GetActorId();
|
||||
|
||||
Collisions.Add(std::move(Collision));
|
||||
}
|
||||
}
|
||||
inline void ACarlaRecorder::AddState(const CarlaRecorderStateTrafficLight &State)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
States.Add(State);
|
||||
}
|
||||
}
|
||||
|
||||
void ACarlaRecorder::AddExistingActors(void)
|
||||
{
|
||||
// registring all existing actors in first frame
|
||||
FActorRegistry Registry = Episode->GetActorRegistry();
|
||||
for (auto &&View : Registry)
|
||||
{
|
||||
const AActor *Actor = View.GetActor();
|
||||
if (Actor != nullptr)
|
||||
{
|
||||
// create event
|
||||
CreateRecorderEventAdd(
|
||||
View.GetActorId(),
|
||||
static_cast<uint8_t>(View.GetActorType()),
|
||||
Actor->GetActorTransform(),
|
||||
View.GetActorInfo()->Description);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ACarlaRecorder::CreateRecorderEventAdd(
|
||||
uint32_t DatabaseId,
|
||||
uint8_t Type,
|
||||
const FTransform &Transform,
|
||||
FActorDescription ActorDescription)
|
||||
{
|
||||
CarlaRecorderActorDescription Description;
|
||||
Description.UId = ActorDescription.UId;
|
||||
Description.Id = ActorDescription.Id;
|
||||
|
||||
// attributes
|
||||
Description.Attributes.reserve(ActorDescription.Variations.Num());
|
||||
for (const auto &item : ActorDescription.Variations)
|
||||
{
|
||||
CarlaRecorderActorAttribute Attr;
|
||||
Attr.Type = static_cast<uint8_t>(item.Value.Type);
|
||||
Attr.Id = item.Value.Id;
|
||||
Attr.Value = item.Value.Value;
|
||||
// check for empty attributes
|
||||
if (!Attr.Id.IsEmpty())
|
||||
{
|
||||
Description.Attributes.emplace_back(std::move(Attr));
|
||||
}
|
||||
}
|
||||
|
||||
// recorder event
|
||||
CarlaRecorderEventAdd RecEvent
|
||||
{
|
||||
DatabaseId,
|
||||
Type,
|
||||
Transform.GetTranslation(),
|
||||
Transform.GetRotation().Euler(),
|
||||
std::move(Description)
|
||||
};
|
||||
AddEvent(std::move(RecEvent));
|
||||
}
|
|
@ -0,0 +1,138 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
// #include "GameFramework/Actor.h"
|
||||
#include <fstream>
|
||||
#include "CarlaRecorderInfo.h"
|
||||
#include "CarlaRecorderFrames.h"
|
||||
#include "CarlaRecorderEventAdd.h"
|
||||
#include "CarlaRecorderEventDel.h"
|
||||
#include "CarlaRecorderEventParent.h"
|
||||
#include "CarlaRecorderCollision.h"
|
||||
#include "CarlaRecorderPosition.h"
|
||||
#include "CarlaRecorderState.h"
|
||||
#include "CarlaRecorderQuery.h"
|
||||
#include "CarlaReplayer.h"
|
||||
#include "Carla/Actor/ActorDescription.h"
|
||||
|
||||
#include "CarlaRecorder.generated.h"
|
||||
|
||||
class AActor;
|
||||
class UCarlaEpisode;
|
||||
|
||||
enum class CarlaRecorderPacketId : uint8_t
|
||||
{
|
||||
FrameStart = 0,
|
||||
FrameEnd,
|
||||
EventAdd,
|
||||
EventDel,
|
||||
EventParent,
|
||||
Collision,
|
||||
Position,
|
||||
State
|
||||
};
|
||||
|
||||
/// Recorder for the simulation
|
||||
UCLASS()
|
||||
class CARLA_API ACarlaRecorder : public AActor
|
||||
{
|
||||
GENERATED_BODY()
|
||||
|
||||
public:
|
||||
|
||||
ACarlaRecorder(void);
|
||||
ACarlaRecorder(const FObjectInitializer &InObjectInitializer);
|
||||
|
||||
// enable / disable
|
||||
bool IsEnabled(void)
|
||||
{
|
||||
return Enabled;
|
||||
}
|
||||
void Enable(void);
|
||||
|
||||
void Disable(void);
|
||||
|
||||
// start / stop
|
||||
std::string Start(FString Path, FString Name, FString MapName);
|
||||
|
||||
void Stop(void);
|
||||
|
||||
void Clear(void);
|
||||
|
||||
void Write(double DeltaSeconds);
|
||||
|
||||
// events
|
||||
void AddEvent(const CarlaRecorderEventAdd &Event);
|
||||
|
||||
void AddEvent(const CarlaRecorderEventDel &Event);
|
||||
|
||||
void AddEvent(const CarlaRecorderEventParent &Event);
|
||||
|
||||
void AddCollision(AActor *Actor1, AActor *Actor2);
|
||||
|
||||
void AddPosition(const CarlaRecorderPosition &Position);
|
||||
|
||||
void AddState(const CarlaRecorderStateTrafficLight &State);
|
||||
|
||||
// set episode
|
||||
void SetEpisode(UCarlaEpisode *ThisEpisode)
|
||||
{
|
||||
Episode = ThisEpisode;
|
||||
Replayer.SetEpisode(ThisEpisode);
|
||||
}
|
||||
|
||||
void CreateRecorderEventAdd(
|
||||
uint32_t DatabaseId,
|
||||
uint8_t Type,
|
||||
const FTransform &Transform,
|
||||
FActorDescription ActorDescription);
|
||||
|
||||
// replayer
|
||||
CarlaReplayer *GetReplayer(void)
|
||||
{
|
||||
return &Replayer;
|
||||
}
|
||||
|
||||
// forwarded to replayer
|
||||
std::string ShowFileInfo(std::string Path, std::string Name);
|
||||
std::string ShowFileCollisions(std::string Path, std::string Name, char Type1, char Type2);
|
||||
std::string ShowFileActorsBlocked(std::string Path, std::string Name, double MinTime = 30, double MinDistance = 10);
|
||||
std::string ReplayFile(std::string Path, std::string Name, double TimeStart, double Duration, uint32_t FollowId);
|
||||
|
||||
void Tick(float DeltaSeconds) final;
|
||||
|
||||
private:
|
||||
|
||||
bool Enabled; // enabled or not
|
||||
|
||||
uint32_t NextCollisionId = 0;
|
||||
|
||||
// files
|
||||
std::ofstream File;
|
||||
|
||||
UCarlaEpisode *Episode = nullptr;
|
||||
|
||||
// structures
|
||||
CarlaRecorderInfo Info;
|
||||
CarlaRecorderFrames Frames;
|
||||
CarlaRecorderEventsAdd EventsAdd;
|
||||
CarlaRecorderEventsDel EventsDel;
|
||||
CarlaRecorderEventsParent EventsParent;
|
||||
CarlaRecorderCollisions Collisions;
|
||||
CarlaRecorderPositions Positions;
|
||||
CarlaRecorderStates States;
|
||||
|
||||
// replayer
|
||||
CarlaReplayer Replayer;
|
||||
|
||||
// query tools
|
||||
CarlaRecorderQuery Query;
|
||||
|
||||
void AddExistingActors(void);
|
||||
|
||||
};
|
|
@ -0,0 +1,68 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaRecorderCollision.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
void CarlaRecorderCollision::Read(std::ifstream &InFile)
|
||||
{
|
||||
// id
|
||||
ReadValue<uint32_t>(InFile, this->Id);
|
||||
// actors database id
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId1);
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId2);
|
||||
// is hero
|
||||
ReadValue<bool>(InFile, this->IsActor1Hero);
|
||||
ReadValue<bool>(InFile, this->IsActor2Hero);
|
||||
}
|
||||
void CarlaRecorderCollision::Write(std::ofstream &OutFile) const
|
||||
{
|
||||
// id
|
||||
WriteValue<uint32_t>(OutFile, this->Id);
|
||||
// actors database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId1);
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId2);
|
||||
// is hero
|
||||
WriteValue<bool>(OutFile, this->IsActor1Hero);
|
||||
WriteValue<bool>(OutFile, this->IsActor2Hero);
|
||||
}
|
||||
bool CarlaRecorderCollision::operator==(const CarlaRecorderCollision &Other) const
|
||||
{
|
||||
return (this->DatabaseId1 == Other.DatabaseId1 &&
|
||||
this->DatabaseId2 == Other.DatabaseId2);
|
||||
}
|
||||
//---------------------------------------------
|
||||
|
||||
void CarlaRecorderCollisions::Clear(void)
|
||||
{
|
||||
Collisions.clear();
|
||||
}
|
||||
|
||||
void CarlaRecorderCollisions::Add(const CarlaRecorderCollision &Collision)
|
||||
{
|
||||
Collisions.insert(std::move(Collision));
|
||||
}
|
||||
|
||||
void CarlaRecorderCollisions::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::Collision));
|
||||
|
||||
// write the packet size
|
||||
uint32_t Total = 2 + Collisions.size() * sizeof(CarlaRecorderCollision);
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write total records
|
||||
Total = Collisions.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
// for (uint16_t i=0; i<Total; ++i)
|
||||
for (auto &Coll : Collisions)
|
||||
{
|
||||
Coll.Write(OutFile);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,54 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include <vector>
|
||||
#include <unordered_set>
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct CarlaRecorderCollision
|
||||
{
|
||||
uint32_t Id;
|
||||
uint32_t DatabaseId1;
|
||||
uint32_t DatabaseId2;
|
||||
bool IsActor1Hero;
|
||||
bool IsActor2Hero;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
void Write(std::ofstream &OutFile) const;
|
||||
// define operator == needed for the 'unordered_set'
|
||||
bool operator==(const CarlaRecorderCollision &Other) const;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
// implement the hash function for the unordered_set of collisions
|
||||
namespace std
|
||||
{
|
||||
template<>
|
||||
struct hash<CarlaRecorderCollision>
|
||||
{
|
||||
std::size_t operator()(const CarlaRecorderCollision& P) const noexcept
|
||||
{
|
||||
std::size_t hash = P.DatabaseId1;
|
||||
hash <<= 32;
|
||||
hash += P.DatabaseId2;
|
||||
return hash;
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
class CarlaRecorderCollisions{
|
||||
|
||||
public:
|
||||
void Add(const CarlaRecorderCollision &Collision);
|
||||
void Clear(void);
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
private:
|
||||
std::unordered_set<CarlaRecorderCollision> Collisions;
|
||||
};
|
|
@ -0,0 +1,104 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaRecorderEventAdd.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
void CarlaRecorderEventAdd::Write(std::ofstream &OutFile) const
|
||||
{
|
||||
// database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
WriteValue<uint8_t>(OutFile, this->Type);
|
||||
|
||||
// transform
|
||||
WriteFVector(OutFile, this->Location);
|
||||
WriteFVector(OutFile, this->Rotation);
|
||||
|
||||
// description type
|
||||
WriteValue<uint32_t>(OutFile, this->Description.UId);
|
||||
WriteFString(OutFile, this->Description.Id);
|
||||
|
||||
// attributes
|
||||
uint16_t Total = this->Description.Attributes.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
{
|
||||
// type
|
||||
WriteValue<uint8_t>(OutFile, this->Description.Attributes[i].Type);
|
||||
WriteFString(OutFile, this->Description.Attributes[i].Id);
|
||||
WriteFString(OutFile, this->Description.Attributes[i].Value);
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaRecorderEventAdd::Read(std::ifstream &InFile)
|
||||
{
|
||||
// database id
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId);
|
||||
|
||||
// database type
|
||||
ReadValue<uint8_t>(InFile, this->Type);
|
||||
|
||||
// transform
|
||||
ReadFVector(InFile, this->Location);
|
||||
ReadFVector(InFile, this->Rotation);
|
||||
|
||||
// description type
|
||||
ReadValue<uint32_t>(InFile, this->Description.UId);
|
||||
ReadFString(InFile, this->Description.Id);
|
||||
|
||||
// attributes
|
||||
uint16_t Total;
|
||||
ReadValue<uint16_t>(InFile, Total);
|
||||
this->Description.Attributes.clear();
|
||||
this->Description.Attributes.reserve(Total);
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
{
|
||||
CarlaRecorderActorAttribute Att;
|
||||
ReadValue<uint8_t>(InFile, Att.Type);
|
||||
ReadFString(InFile, Att.Id);
|
||||
ReadFString(InFile, Att.Value);
|
||||
this->Description.Attributes.push_back(std::move(Att));
|
||||
}
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
inline void CarlaRecorderEventsAdd::Clear(void)
|
||||
{
|
||||
Events.clear();
|
||||
}
|
||||
|
||||
inline void CarlaRecorderEventsAdd::Add(const CarlaRecorderEventAdd &Event)
|
||||
{
|
||||
Events.push_back(std::move(Event));
|
||||
}
|
||||
|
||||
void CarlaRecorderEventsAdd::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::EventAdd));
|
||||
|
||||
std::streampos PosStart = OutFile.tellp();
|
||||
|
||||
// write a dummy packet size
|
||||
uint32_t Total = 0;
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write total records
|
||||
Total = Events.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
Events[i].Write(OutFile);
|
||||
|
||||
// write the real packet size
|
||||
std::streampos PosEnd = OutFile.tellp();
|
||||
Total = PosEnd - PosStart - sizeof(uint32_t);
|
||||
OutFile.seekp(PosStart, std::ios::beg);
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
OutFile.seekp(PosEnd, std::ios::beg);
|
||||
}
|
|
@ -0,0 +1,48 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include <vector>
|
||||
|
||||
struct CarlaRecorderActorAttribute
|
||||
{
|
||||
uint8_t Type; // EActorAttributeType
|
||||
FString Id; // string
|
||||
FString Value; // string
|
||||
};
|
||||
|
||||
struct CarlaRecorderActorDescription
|
||||
{
|
||||
uint32_t UId;
|
||||
FString Id; // string
|
||||
std::vector<CarlaRecorderActorAttribute> Attributes;
|
||||
};
|
||||
|
||||
struct CarlaRecorderEventAdd
|
||||
{
|
||||
uint32_t DatabaseId;
|
||||
uint8_t Type;
|
||||
FVector Location;
|
||||
FVector Rotation;
|
||||
CarlaRecorderActorDescription Description;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
void Write(std::ofstream &OutFile) const;
|
||||
};
|
||||
|
||||
class CarlaRecorderEventsAdd
|
||||
{
|
||||
|
||||
public:
|
||||
void Add(const CarlaRecorderEventAdd &Event);
|
||||
void Clear(void);
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
private:
|
||||
std::vector<CarlaRecorderEventAdd> Events;
|
||||
};
|
|
@ -0,0 +1,60 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaRecorderEventDel.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
void CarlaRecorderEventDel::Read(std::ifstream &InFile)
|
||||
{
|
||||
// database id
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId);
|
||||
}
|
||||
void CarlaRecorderEventDel::Write(std::ofstream &OutFile) const
|
||||
{
|
||||
// database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
inline void CarlaRecorderEventsDel::Clear(void)
|
||||
{
|
||||
Events.clear();
|
||||
}
|
||||
|
||||
inline void CarlaRecorderEventsDel::Add(const CarlaRecorderEventDel &Event)
|
||||
{
|
||||
Events.push_back(std::move(Event));
|
||||
}
|
||||
|
||||
void CarlaRecorderEventsDel::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::EventDel));
|
||||
|
||||
std::streampos PosStart = OutFile.tellp();
|
||||
|
||||
// write a dummy packet size
|
||||
uint32_t Total = 0;
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write total records
|
||||
Total = Events.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
{
|
||||
Events[i].Write(OutFile);
|
||||
}
|
||||
|
||||
// write the real packet size
|
||||
std::streampos PosEnd = OutFile.tellp();
|
||||
Total = PosEnd - PosStart - sizeof(uint32_t);
|
||||
OutFile.seekp(PosStart, std::ios::beg);
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
OutFile.seekp(PosEnd, std::ios::beg);
|
||||
}
|
|
@ -0,0 +1,30 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include <vector>
|
||||
|
||||
struct CarlaRecorderEventDel
|
||||
{
|
||||
uint32_t DatabaseId;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
void Write(std::ofstream &OutFile) const;
|
||||
};
|
||||
|
||||
class CarlaRecorderEventsDel
|
||||
{
|
||||
|
||||
public:
|
||||
void Add(const CarlaRecorderEventDel &Event);
|
||||
void Clear(void);
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
private:
|
||||
std::vector<CarlaRecorderEventDel> Events;
|
||||
};
|
|
@ -0,0 +1,65 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaRecorderEventParent.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
|
||||
void CarlaRecorderEventParent::Read(std::ifstream &InFile)
|
||||
{
|
||||
// database id
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId);
|
||||
// database id parent
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseIdParent);
|
||||
}
|
||||
void CarlaRecorderEventParent::Write(std::ofstream &OutFile) const
|
||||
{
|
||||
// database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
// database id parent
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseIdParent);
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
inline void CarlaRecorderEventsParent::Clear(void)
|
||||
{
|
||||
Events.clear();
|
||||
}
|
||||
|
||||
inline void CarlaRecorderEventsParent::Add(const CarlaRecorderEventParent &Event)
|
||||
{
|
||||
Events.push_back(std::move(Event));
|
||||
}
|
||||
|
||||
void CarlaRecorderEventsParent::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::EventParent));
|
||||
|
||||
std::streampos PosStart = OutFile.tellp();
|
||||
|
||||
// write a dummy packet size
|
||||
uint32_t Total = 0;
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write total records
|
||||
Total = Events.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
{
|
||||
Events[i].Write(OutFile);
|
||||
}
|
||||
|
||||
// write the real packet size
|
||||
std::streampos PosEnd = OutFile.tellp();
|
||||
Total = PosEnd - PosStart - sizeof(uint32_t);
|
||||
OutFile.seekp(PosStart, std::ios::beg);
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
OutFile.seekp(PosEnd, std::ios::beg);
|
||||
}
|
|
@ -0,0 +1,31 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include <vector>
|
||||
|
||||
struct CarlaRecorderEventParent
|
||||
{
|
||||
uint32_t DatabaseId;
|
||||
uint32_t DatabaseIdParent;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
void Write(std::ofstream &OutFile) const;
|
||||
};
|
||||
|
||||
class CarlaRecorderEventsParent
|
||||
{
|
||||
|
||||
public:
|
||||
void Add(const CarlaRecorderEventParent &Event);
|
||||
void Clear(void);
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
private:
|
||||
std::vector<CarlaRecorderEventParent> Events;
|
||||
};
|
|
@ -0,0 +1,91 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaRecorderFrames.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
void CarlaRecorderFrame::Read(std::ifstream &InFile)
|
||||
{
|
||||
ReadValue<CarlaRecorderFrame>(InFile, *this);
|
||||
}
|
||||
|
||||
void CarlaRecorderFrame::Write(std::ofstream &OutFile)
|
||||
{
|
||||
WriteValue<CarlaRecorderFrame>(OutFile, *this);
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
|
||||
CarlaRecorderFrames::CarlaRecorderFrames(void)
|
||||
{
|
||||
Reset();
|
||||
}
|
||||
|
||||
void CarlaRecorderFrames::Reset(void)
|
||||
{
|
||||
Frame.Id = 0;
|
||||
Frame.DurationThis = 0.0f;
|
||||
Frame.Elapsed = 0.0f;
|
||||
OffsetPreviousFrame = 0;
|
||||
}
|
||||
|
||||
void CarlaRecorderFrames::SetFrame(double DeltaSeconds)
|
||||
{
|
||||
if (Frame.Id == 0)
|
||||
{
|
||||
Frame.Elapsed = 0.0f;
|
||||
Frame.DurationThis = 0.0f;
|
||||
}
|
||||
else
|
||||
{
|
||||
Frame.DurationThis = DeltaSeconds;
|
||||
Frame.Elapsed += DeltaSeconds;
|
||||
}
|
||||
|
||||
++Frame.Id;
|
||||
}
|
||||
|
||||
void CarlaRecorderFrames::WriteStart(std::ofstream &OutFile)
|
||||
{
|
||||
std::streampos Pos, Offset;
|
||||
double Dummy = -1.0f;
|
||||
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::FrameStart));
|
||||
|
||||
// write the packet size
|
||||
uint32_t Total = sizeof(CarlaRecorderFrame);
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write frame record
|
||||
WriteValue<uint64_t>(OutFile, Frame.Id);
|
||||
Offset = OutFile.tellp();
|
||||
WriteValue<double>(OutFile, Dummy);
|
||||
WriteValue<double>(OutFile, Frame.Elapsed);
|
||||
|
||||
// we need to write this duration to previous frame
|
||||
if (OffsetPreviousFrame > 0)
|
||||
{
|
||||
Pos = OutFile.tellp();
|
||||
OutFile.seekp(OffsetPreviousFrame, std::ios::beg);
|
||||
WriteValue<double>(OutFile, Frame.DurationThis);
|
||||
OutFile.seekp(Pos, std::ios::beg);
|
||||
}
|
||||
|
||||
// save position for next actualization
|
||||
OffsetPreviousFrame = Offset;
|
||||
}
|
||||
|
||||
void CarlaRecorderFrames::WriteEnd(std::ofstream &OutFile)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::FrameEnd));
|
||||
|
||||
// write the packet size (0)
|
||||
uint32_t Total = 0;
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
}
|
|
@ -0,0 +1,42 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct CarlaRecorderFrame
|
||||
{
|
||||
uint64_t Id;
|
||||
double DurationThis;
|
||||
double Elapsed;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class CarlaRecorderFrames
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
CarlaRecorderFrames(void);
|
||||
void Reset();
|
||||
|
||||
void SetFrame(double DeltaSeconds);
|
||||
|
||||
void WriteStart(std::ofstream &OutFile);
|
||||
void WriteEnd(std::ofstream &OutFile);
|
||||
|
||||
private:
|
||||
|
||||
CarlaRecorderFrame Frame;
|
||||
std::streampos OffsetPreviousFrame;
|
||||
};
|
|
@ -0,0 +1,82 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include <vector>
|
||||
|
||||
#include "UnrealString.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
// create a temporal buffer to convert from and to FString and bytes
|
||||
static std::vector<uint8_t> CarlaRecorderHelperBuffer;
|
||||
|
||||
// ------
|
||||
// write
|
||||
// ------
|
||||
|
||||
// write binary data from FVector
|
||||
void WriteFVector(std::ofstream &OutFile, const FVector &InObj)
|
||||
{
|
||||
WriteValue<float>(OutFile, InObj.X);
|
||||
WriteValue<float>(OutFile, InObj.Y);
|
||||
WriteValue<float>(OutFile, InObj.Z);
|
||||
}
|
||||
|
||||
// write binary data from FTransform
|
||||
// void WriteFTransform(std::ofstream &OutFile, const FTransform &InObj){
|
||||
// WriteFVector(OutFile, InObj.GetTranslation());
|
||||
// WriteFVector(OutFile, InObj.GetRotation().Euler());
|
||||
// }
|
||||
|
||||
// write binary data from FString (length + text)
|
||||
void WriteFString(std::ofstream &OutFile, const FString &InObj)
|
||||
{
|
||||
// encode the string to UTF8 to know the final length
|
||||
FTCHARToUTF8 EncodedString(*InObj);
|
||||
int16_t Length = EncodedString.Length();
|
||||
// write
|
||||
WriteValue<uint16_t>(OutFile, Length);
|
||||
OutFile.write(reinterpret_cast<char *>(TCHAR_TO_UTF8(*InObj)), Length);
|
||||
}
|
||||
|
||||
// -----
|
||||
// read
|
||||
// -----
|
||||
|
||||
// read binary data to FVector
|
||||
void ReadFVector(std::ifstream &InFile, FVector &OutObj)
|
||||
{
|
||||
ReadValue<float>(InFile, OutObj.X);
|
||||
ReadValue<float>(InFile, OutObj.Y);
|
||||
ReadValue<float>(InFile, OutObj.Z);
|
||||
}
|
||||
|
||||
// read binary data to FTransform
|
||||
// void ReadFTransform(std::ifstream &InFile, FTransform &OutObj){
|
||||
// FVector Vec;
|
||||
// ReadFVector(InFile, Vec);
|
||||
// OutObj.SetTranslation(Vec);
|
||||
// ReadFVector(InFile, Vec);
|
||||
// OutObj.GetRotation().MakeFromEuler(Vec);
|
||||
// }
|
||||
|
||||
// read binary data to FString (length + text)
|
||||
void ReadFString(std::ifstream &InFile, FString &OutObj)
|
||||
{
|
||||
uint16_t Length;
|
||||
ReadValue<uint16_t>(InFile, Length);
|
||||
// make room in vector buffer
|
||||
if (CarlaRecorderHelperBuffer.capacity() < Length + 1)
|
||||
{
|
||||
CarlaRecorderHelperBuffer.reserve(Length + 1);
|
||||
}
|
||||
CarlaRecorderHelperBuffer.clear();
|
||||
// initialize the vector space with 0
|
||||
CarlaRecorderHelperBuffer.resize(Length + 1);
|
||||
// read
|
||||
InFile.read(reinterpret_cast<char *>(CarlaRecorderHelperBuffer.data()), Length);
|
||||
// convert from UTF8 to FString
|
||||
OutObj = FString(UTF8_TO_TCHAR(CarlaRecorderHelperBuffer.data()));
|
||||
}
|
|
@ -0,0 +1,47 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
|
||||
// ---------
|
||||
// recorder
|
||||
// ---------
|
||||
|
||||
// write binary data (using sizeof())
|
||||
template <typename T>
|
||||
void WriteValue(std::ofstream &OutFile, const T &InObj)
|
||||
{
|
||||
OutFile.write(reinterpret_cast<const char *>(&InObj), sizeof(T));
|
||||
}
|
||||
|
||||
// write binary data from FVector
|
||||
void WriteFVector(std::ofstream &OutFile, const FVector &InObj);
|
||||
|
||||
// write binary data from FTransform
|
||||
// void WriteFTransform(std::ofstream &OutFile, const FTransform &InObj);
|
||||
// write binary data from FString (length + text)
|
||||
void WriteFString(std::ofstream &OutFile, const FString &InObj);
|
||||
|
||||
// ---------
|
||||
// replayer
|
||||
// ---------
|
||||
|
||||
// read binary data (using sizeof())
|
||||
template <typename T>
|
||||
void ReadValue(std::ifstream &InFile, T &OutObj)
|
||||
{
|
||||
InFile.read(reinterpret_cast<char *>(&OutObj), sizeof(T));
|
||||
}
|
||||
|
||||
// read binary data from FVector
|
||||
void ReadFVector(std::ifstream &InFile, FVector &OutObj);
|
||||
|
||||
// read binary data from FTransform
|
||||
// void ReadTransform(std::ifstream &InFile, FTransform &OutObj);
|
||||
// read binary data from FString (length + text)
|
||||
void ReadFString(std::ifstream &InFile, FString &OutObj);
|
|
@ -0,0 +1,36 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
#include <fstream>
|
||||
#include <ctime>
|
||||
|
||||
struct CarlaRecorderInfo
|
||||
{
|
||||
uint16_t Version;
|
||||
FString Magic;
|
||||
std::time_t Date;
|
||||
FString Mapfile;
|
||||
|
||||
void Read(std::ifstream &File)
|
||||
{
|
||||
ReadValue<uint16_t>(File, Version);
|
||||
ReadFString(File, Magic);
|
||||
ReadValue<std::time_t>(File, Date);
|
||||
ReadFString(File, Mapfile);
|
||||
}
|
||||
|
||||
void Write(std::ofstream &File)
|
||||
{
|
||||
WriteValue<uint16_t>(File, Version);
|
||||
WriteFString(File, Magic);
|
||||
WriteValue<std::time_t>(File, Date);
|
||||
WriteFString(File, Mapfile);
|
||||
}
|
||||
};
|
|
@ -0,0 +1,59 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaRecorderPosition.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
void CarlaRecorderPosition::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
// transform
|
||||
WriteFVector(OutFile, this->Location);
|
||||
WriteFVector(OutFile, this->Rotation);
|
||||
}
|
||||
void CarlaRecorderPosition::Read(std::ifstream &InFile)
|
||||
{
|
||||
// database id
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId);
|
||||
// transform
|
||||
ReadFVector(InFile, this->Location);
|
||||
ReadFVector(InFile, this->Rotation);
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
|
||||
void CarlaRecorderPositions::Clear(void)
|
||||
{
|
||||
Positions.clear();
|
||||
}
|
||||
|
||||
void CarlaRecorderPositions::Add(const CarlaRecorderPosition &Position)
|
||||
{
|
||||
Positions.push_back(Position);
|
||||
}
|
||||
|
||||
void CarlaRecorderPositions::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::Position));
|
||||
|
||||
// write the packet size
|
||||
uint32_t Total = 2 + Positions.size() * sizeof(CarlaRecorderPosition);
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write total records
|
||||
Total = Positions.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
// write records
|
||||
if (Total > 0)
|
||||
{
|
||||
OutFile.write(reinterpret_cast<const char *>(Positions.data()),
|
||||
Positions.size() * sizeof(CarlaRecorderPosition));
|
||||
}
|
||||
}
|
|
@ -0,0 +1,39 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include <vector>
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct CarlaRecorderPosition
|
||||
{
|
||||
uint32_t DatabaseId;
|
||||
FVector Location;
|
||||
FVector Rotation;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class CarlaRecorderPositions
|
||||
{
|
||||
public:
|
||||
|
||||
void Add(const CarlaRecorderPosition &InObj);
|
||||
|
||||
void Clear(void);
|
||||
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
private:
|
||||
|
||||
std::vector<CarlaRecorderPosition> Positions;
|
||||
};
|
|
@ -0,0 +1,556 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
#include <ctime>
|
||||
#include <sstream>
|
||||
|
||||
inline bool CarlaRecorderQuery::ReadHeader(void)
|
||||
{
|
||||
if (File.eof())
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
ReadValue<char>(File, Header.Id);
|
||||
ReadValue<uint32_t>(File, Header.Size);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
inline void CarlaRecorderQuery::SkipPacket(void)
|
||||
{
|
||||
File.seekg(Header.Size, std::ios::cur);
|
||||
}
|
||||
|
||||
inline bool CarlaRecorderQuery::CheckFileInfo(std::stringstream &Info)
|
||||
{
|
||||
// read Info
|
||||
RecInfo.Read(File);
|
||||
|
||||
// check magic string
|
||||
if (RecInfo.Magic != "CARLA_RECORDER")
|
||||
{
|
||||
Info << "File is not a CARLA recorder" << std::endl;
|
||||
return false;
|
||||
}
|
||||
|
||||
// show general Info
|
||||
Info << "Version: " << RecInfo.Version << std::endl;
|
||||
Info << "Map: " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl;
|
||||
tm *TimeInfo = localtime(&RecInfo.Date);
|
||||
char DateStr[100];
|
||||
strftime(DateStr, sizeof(DateStr), "%x %X", TimeInfo);
|
||||
Info << "Date: " << DateStr << std::endl << std::endl;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
|
||||
{
|
||||
std::stringstream Info;
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
uint16_t i, Total;
|
||||
bool bFramePrinted;
|
||||
|
||||
// lambda for repeating task
|
||||
auto PrintFrame = [this](std::stringstream &Info)
|
||||
{
|
||||
Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n";
|
||||
// Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds (offset 0x" << std::hex << File.tellg() << std::dec << ")\n";
|
||||
};
|
||||
|
||||
if (!CheckFileInfo(Info))
|
||||
return Info.str();
|
||||
|
||||
// parse only frames
|
||||
while (File)
|
||||
{
|
||||
|
||||
// get header
|
||||
if (!ReadHeader())
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
// check for a frame packet
|
||||
switch (Header.Id)
|
||||
{
|
||||
// frame
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameStart):
|
||||
Frame.Read(File);
|
||||
bFramePrinted = false;
|
||||
break;
|
||||
|
||||
// events add
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventAdd):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && !bFramePrinted)
|
||||
{
|
||||
PrintFrame(Info);
|
||||
bFramePrinted = true;
|
||||
}
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
// add
|
||||
EventAdd.Read(File);
|
||||
Info << " Create " << EventAdd.DatabaseId << ": " << TCHAR_TO_UTF8(*EventAdd.Description.Id) <<
|
||||
" (" <<
|
||||
static_cast<int>(EventAdd.Type) << ") at (" << EventAdd.Location.X << ", " <<
|
||||
EventAdd.Location.Y << ", " << EventAdd.Location.Z << ")" << std::endl;
|
||||
for (auto &Att : EventAdd.Description.Attributes)
|
||||
{
|
||||
Info << " " << TCHAR_TO_UTF8(*Att.Id) << " = " << TCHAR_TO_UTF8(*Att.Value) << std::endl;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
// events del
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventDel):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && !bFramePrinted)
|
||||
{
|
||||
PrintFrame(Info);
|
||||
bFramePrinted = true;
|
||||
}
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventDel.Read(File);
|
||||
Info << " Destroy " << EventDel.DatabaseId << "\n";
|
||||
}
|
||||
break;
|
||||
|
||||
// events parenting
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventParent):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && !bFramePrinted)
|
||||
{
|
||||
PrintFrame(Info);
|
||||
bFramePrinted = true;
|
||||
}
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventParent.Read(File);
|
||||
Info << " Parenting " << EventParent.DatabaseId << " with " << EventParent.DatabaseId <<
|
||||
" (parent)\n";
|
||||
}
|
||||
break;
|
||||
|
||||
// collisions
|
||||
case static_cast<char>(CarlaRecorderPacketId::Collision):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && !bFramePrinted)
|
||||
{
|
||||
PrintFrame(Info);
|
||||
bFramePrinted = true;
|
||||
}
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
Collision.Read(File);
|
||||
Info << " Collision id " << Collision.Id << " between " << Collision.DatabaseId1;
|
||||
if (Collision.IsActor1Hero)
|
||||
Info << " (hero) ";
|
||||
Info << " with " << Collision.DatabaseId2;
|
||||
if (Collision.IsActor2Hero)
|
||||
Info << " (hero) ";
|
||||
Info << std::endl;
|
||||
}
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::Position):
|
||||
// Info << "Positions\n";
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::State):
|
||||
if (bShowAll)
|
||||
{
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && !bFramePrinted)
|
||||
{
|
||||
PrintFrame(Info);
|
||||
bFramePrinted = true;
|
||||
}
|
||||
Info << " State traffic lights: " << Total << std::endl;
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
StateTraffic.Read(File);
|
||||
Info << " Id: " << StateTraffic.DatabaseId << " state: " << static_cast<char>(0x30 + StateTraffic.State) << " frozen: " <<
|
||||
StateTraffic.IsFrozen << " elapsedTime: " << StateTraffic.ElapsedTime << std::endl;
|
||||
}
|
||||
}
|
||||
else
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// frame end
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameEnd):
|
||||
// do nothing, it is empty
|
||||
break;
|
||||
|
||||
default:
|
||||
// skip packet
|
||||
Info << "Unknown packet id: " << Header.Id << " at offset " << File.tellg() << std::endl;
|
||||
SkipPacket();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
Info << "\nFrames: " << Frame.Id << "\n";
|
||||
Info << "Duration: " << Frame.Elapsed << " seconds\n";
|
||||
|
||||
File.close();
|
||||
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Category1, char Category2)
|
||||
{
|
||||
std::stringstream Info;
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
if (!CheckFileInfo(Info))
|
||||
return Info.str();
|
||||
|
||||
// other, vehicle, walkers, trafficLight, hero, any
|
||||
char Categories[] = { 'o', 'v', 'w', 't', 'h', 'a' };
|
||||
uint16_t i, Total;
|
||||
struct ReplayerActorInfo
|
||||
{
|
||||
uint8_t Type;
|
||||
FString Id;
|
||||
};
|
||||
std::unordered_map<uint32_t, ReplayerActorInfo> Actors;
|
||||
struct PairHash
|
||||
{
|
||||
std::size_t operator()(const std::pair<uint32_t, uint32_t>& P) const
|
||||
{
|
||||
std::size_t hash = P.first;
|
||||
hash <<= 32;
|
||||
hash += P.second;
|
||||
return hash;
|
||||
}
|
||||
};
|
||||
std::unordered_set<std::pair<uint32_t, uint32_t>, PairHash > oldCollisions, newCollisions;
|
||||
|
||||
// header
|
||||
Info << std::setw(8) << "Time";
|
||||
Info << " " << std::setw(6) << "Types";
|
||||
Info << " " << std::setw(6) << std::right << "Id";
|
||||
Info << " " << std::setw(35) << std::left << "Actor 1";
|
||||
Info << " " << std::setw(6) << std::right << "Id";
|
||||
Info << " " << std::setw(35) << std::left << "Actor 2";
|
||||
Info << std::endl;
|
||||
|
||||
// parse only frames
|
||||
while (File)
|
||||
{
|
||||
|
||||
// get header
|
||||
if (!ReadHeader())
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
// check for a frame packet
|
||||
switch (Header.Id)
|
||||
{
|
||||
// frame
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameStart):
|
||||
Frame.Read(File);
|
||||
// exchange sets of collisions (to know when a collision is new or continue from previous frame)
|
||||
oldCollisions = std::move(newCollisions);
|
||||
newCollisions.clear();
|
||||
break;
|
||||
|
||||
// events add
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventAdd):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
// add
|
||||
EventAdd.Read(File);
|
||||
Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id };
|
||||
}
|
||||
break;
|
||||
|
||||
// events del
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventDel):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventDel.Read(File);
|
||||
Actors.erase(EventAdd.DatabaseId);
|
||||
}
|
||||
break;
|
||||
|
||||
// events parenting
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventParent):
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// collisions
|
||||
case static_cast<char>(CarlaRecorderPacketId::Collision):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
Collision.Read(File);
|
||||
|
||||
int Valid = 0;
|
||||
// get categories for both actors
|
||||
uint8_t Type1 = Categories[Actors[Collision.DatabaseId1].Type];
|
||||
uint8_t Type2 = Categories[Actors[Collision.DatabaseId2].Type];
|
||||
|
||||
// filter actor 1
|
||||
if (Category1 == 'a')
|
||||
++Valid;
|
||||
else if (Category1 == Type1)
|
||||
++Valid;
|
||||
else if (Category1 == 'h' && Collision.IsActor1Hero)
|
||||
++Valid;
|
||||
|
||||
// filter actor 2
|
||||
if (Category2 == 'a')
|
||||
++Valid;
|
||||
else if (Category2 == Type2)
|
||||
++Valid;
|
||||
else if (Category2 == 'h' && Collision.IsActor2Hero)
|
||||
++Valid;
|
||||
|
||||
// only show if both actors has passed the filter
|
||||
if (Valid == 2)
|
||||
{
|
||||
// check if we need to show as a starting collision or it is a continuation one
|
||||
auto collisionPair = std::make_pair(Collision.DatabaseId1, Collision.DatabaseId2);
|
||||
if (oldCollisions.count(collisionPair) == 0)
|
||||
{
|
||||
// Info << std::setw(5) << Collision.Id << " ";
|
||||
Info << std::setw(8) << std::setprecision(0) << std::right << std::fixed << Frame.Elapsed;
|
||||
Info << " " << " " << Type1 << " " << Type2 << " ";
|
||||
Info << " " << std::setw(6) << std::right << Collision.DatabaseId1;
|
||||
Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId1].Id);
|
||||
Info << " " << std::setw(6) << std::right << Collision.DatabaseId2;
|
||||
Info << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Collision.DatabaseId2].Id);
|
||||
//Info << std::setw(8) << Frame.Id;
|
||||
Info << std::endl;
|
||||
}
|
||||
// save current collision
|
||||
newCollisions.insert(collisionPair);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::Position):
|
||||
// Info << "Positions\n";
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::State):
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// frame end
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameEnd):
|
||||
// do nothing, it is empty
|
||||
break;
|
||||
|
||||
default:
|
||||
// skip packet
|
||||
Info << "Unknown packet id: " << Header.Id << " at offset " << File.tellg() << std::endl;
|
||||
SkipPacket();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
Info << "\nFrames: " << Frame.Id << "\n";
|
||||
Info << "Duration: " << Frame.Elapsed << " seconds\n";
|
||||
|
||||
File.close();
|
||||
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTime, double MinDistance)
|
||||
{
|
||||
std::stringstream Info;
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
if (!CheckFileInfo(Info))
|
||||
return Info.str();
|
||||
|
||||
// other, vehicle, walkers, trafficLight, hero, any
|
||||
uint16_t i, Total;
|
||||
struct ReplayerActorInfo
|
||||
{
|
||||
uint8_t Type;
|
||||
FString Id;
|
||||
FVector LastPosition;
|
||||
double Time;
|
||||
double Duration;
|
||||
};
|
||||
std::unordered_map<uint32_t, ReplayerActorInfo> Actors;
|
||||
// to be able to sort the results by the duration of each actor (decreasing order)
|
||||
std::multimap<double, std::string, std::greater<double>> Results;
|
||||
|
||||
// header
|
||||
Info << std::setw(8) << "Time";
|
||||
Info << " " << std::setw(6) << "Id";
|
||||
Info << " " << std::setw(35) << std::left << "Actor";
|
||||
Info << " " << std::setw(10) << std::right << "Duration";
|
||||
Info << std::endl;
|
||||
|
||||
// parse only frames
|
||||
while (File)
|
||||
{
|
||||
|
||||
// get header
|
||||
if (!ReadHeader())
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
// check for a frame packet
|
||||
switch (Header.Id)
|
||||
{
|
||||
// frame
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameStart):
|
||||
Frame.Read(File);
|
||||
break;
|
||||
|
||||
// events add
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventAdd):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
// add
|
||||
EventAdd.Read(File);
|
||||
Actors[EventAdd.DatabaseId] = ReplayerActorInfo { EventAdd.Type, EventAdd.Description.Id };
|
||||
}
|
||||
break;
|
||||
|
||||
// events del
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventDel):
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventDel.Read(File);
|
||||
Actors.erase(EventAdd.DatabaseId);
|
||||
}
|
||||
break;
|
||||
|
||||
// events parenting
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventParent):
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// collisions
|
||||
case static_cast<char>(CarlaRecorderPacketId::Collision):
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::Position):
|
||||
// read all positions
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i=0; i<Total; ++i)
|
||||
{
|
||||
Position.Read(File);
|
||||
// check if actor moved less than a distance
|
||||
if (FVector::Distance(Actors[Position.DatabaseId].LastPosition, Position.Location) < MinDistance)
|
||||
{
|
||||
// actor stopped
|
||||
if (Actors[Position.DatabaseId].Duration == 0)
|
||||
Actors[Position.DatabaseId].Time = Frame.Elapsed;
|
||||
Actors[Position.DatabaseId].Duration += Frame.DurationThis;
|
||||
}
|
||||
else
|
||||
{
|
||||
// check to show info
|
||||
if (Actors[Position.DatabaseId].Duration >= MinTime)
|
||||
{
|
||||
std::stringstream Result;
|
||||
Result << std::setw(8) << std::setprecision(0) << std::fixed << Actors[Position.DatabaseId].Time;
|
||||
Result << " " << std::setw(6) << Position.DatabaseId;
|
||||
Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actors[Position.DatabaseId].Id);
|
||||
Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actors[Position.DatabaseId].Duration;
|
||||
Result << std::endl;
|
||||
Results.insert(std::make_pair(Actors[Position.DatabaseId].Duration, Result.str()));
|
||||
}
|
||||
// actor moving
|
||||
Actors[Position.DatabaseId].Duration = 0;
|
||||
Actors[Position.DatabaseId].LastPosition = Position.Location;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::State):
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// frame end
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameEnd):
|
||||
// do nothing, it is empty
|
||||
break;
|
||||
|
||||
default:
|
||||
// skip packet
|
||||
Info << "Unknown packet id: " << Header.Id << " at offset " << File.tellg() << std::endl;
|
||||
SkipPacket();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
// show actors stopped that were not moving again
|
||||
for (auto &Actor : Actors)
|
||||
{
|
||||
// check to show info
|
||||
if (Actor.second.Duration >= MinTime)
|
||||
{
|
||||
std::stringstream Result;
|
||||
Result << std::setw(8) << std::setprecision(0) << std::fixed << Actor.second.Time;
|
||||
Result << " " << std::setw(6) << Actor.first;
|
||||
Result << " " << std::setw(35) << std::left << TCHAR_TO_UTF8(*Actor.second.Id);
|
||||
Result << " " << std::setw(10) << std::setprecision(0) << std::fixed << std::right << Actor.second.Duration;
|
||||
Result << std::endl;
|
||||
Results.insert(std::make_pair(Actor.second.Duration, Result.str()));
|
||||
}
|
||||
}
|
||||
|
||||
// show the result
|
||||
for (auto &Result : Results)
|
||||
{
|
||||
Info << Result.second;
|
||||
}
|
||||
|
||||
Info << "\nFrames: " << Frame.Id << "\n";
|
||||
Info << "Duration: " << Frame.Elapsed << " seconds\n";
|
||||
|
||||
File.close();
|
||||
|
||||
return Info.str();
|
||||
}
|
|
@ -0,0 +1,60 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include "CarlaRecorderInfo.h"
|
||||
#include "CarlaRecorderFrames.h"
|
||||
#include "CarlaRecorderEventAdd.h"
|
||||
#include "CarlaRecorderEventDel.h"
|
||||
#include "CarlaRecorderEventParent.h"
|
||||
#include "CarlaRecorderCollision.h"
|
||||
#include "CarlaRecorderPosition.h"
|
||||
#include "CarlaRecorderState.h"
|
||||
|
||||
class CarlaRecorderQuery
|
||||
{
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct Header
|
||||
{
|
||||
char Id;
|
||||
uint32_t Size;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
public:
|
||||
|
||||
// get general info
|
||||
std::string QueryInfo(std::string Filename, bool bShowAll = false);
|
||||
// get info about collisions
|
||||
std::string QueryCollisions(std::string Filename, char Category1 = 'a', char Category2 = 'a');
|
||||
// get info about blocked actors
|
||||
std::string QueryBlocked(std::string Filename, double MinTime = 30, double MinDistance = 10);
|
||||
|
||||
private:
|
||||
|
||||
std::ifstream File;
|
||||
Header Header;
|
||||
CarlaRecorderInfo RecInfo;
|
||||
CarlaRecorderFrame Frame;
|
||||
CarlaRecorderEventAdd EventAdd;
|
||||
CarlaRecorderEventDel EventDel;
|
||||
CarlaRecorderEventParent EventParent;
|
||||
CarlaRecorderPosition Position;
|
||||
CarlaRecorderCollision Collision;
|
||||
CarlaRecorderStateTrafficLight StateTraffic;
|
||||
|
||||
// read next header packet
|
||||
bool ReadHeader(void);
|
||||
|
||||
// skip current packet
|
||||
void SkipPacket(void);
|
||||
|
||||
// read the start info structure and check the magic string
|
||||
bool CheckFileInfo(std::stringstream &Info);
|
||||
};
|
|
@ -0,0 +1,56 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaRecorderState.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
void CarlaRecorderStateTrafficLight::Write(std::ofstream &OutFile)
|
||||
{
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
WriteValue<bool>(OutFile, this->IsFrozen);
|
||||
WriteValue<float>(OutFile, this->ElapsedTime);
|
||||
WriteValue<char>(OutFile, this->State);
|
||||
}
|
||||
|
||||
void CarlaRecorderStateTrafficLight::Read(std::ifstream &InFile)
|
||||
{
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId);
|
||||
ReadValue<bool>(InFile, this->IsFrozen);
|
||||
ReadValue<float>(InFile, this->ElapsedTime);
|
||||
ReadValue<char>(InFile, this->State);
|
||||
}
|
||||
|
||||
// ---------------------------------------------
|
||||
|
||||
void CarlaRecorderStates::Clear(void)
|
||||
{
|
||||
StatesTrafficLights.clear();
|
||||
}
|
||||
|
||||
void CarlaRecorderStates::Add(const CarlaRecorderStateTrafficLight &State)
|
||||
{
|
||||
StatesTrafficLights.push_back(std::move(State));
|
||||
}
|
||||
|
||||
void CarlaRecorderStates::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::State));
|
||||
|
||||
// write the packet size
|
||||
uint32_t Total = 2 + StatesTrafficLights.size() * sizeof(CarlaRecorderStateTrafficLight);
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write total records
|
||||
Total = StatesTrafficLights.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i = 0; i < Total; ++i)
|
||||
{
|
||||
StatesTrafficLights[i].Write(OutFile);
|
||||
}
|
||||
}
|
|
@ -0,0 +1,42 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
|
||||
#pragma pack(push, 1)
|
||||
|
||||
struct CarlaRecorderStateTrafficLight
|
||||
{
|
||||
uint32_t DatabaseId;
|
||||
bool IsFrozen;
|
||||
float ElapsedTime;
|
||||
char State;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
};
|
||||
|
||||
#pragma pack(pop)
|
||||
|
||||
class CarlaRecorderStates
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
void Add(const CarlaRecorderStateTrafficLight &State);
|
||||
|
||||
void Clear(void);
|
||||
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
private:
|
||||
|
||||
std::vector<CarlaRecorderStateTrafficLight> StatesTrafficLights;
|
||||
};
|
|
@ -0,0 +1,509 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaReplayer.h"
|
||||
#include "CarlaRecorder.h"
|
||||
|
||||
#include <ctime>
|
||||
#include <sstream>
|
||||
|
||||
void CarlaReplayer::Stop(bool bKeepActors)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
Enabled = false;
|
||||
|
||||
// destroy actors if event was recorded?
|
||||
if (!bKeepActors)
|
||||
{
|
||||
ProcessToTime(TotalTime);
|
||||
}
|
||||
|
||||
File.close();
|
||||
|
||||
// callback
|
||||
Helper.ProcessReplayerFinish(bKeepActors);
|
||||
}
|
||||
|
||||
if (!bKeepActors)
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Replayer stop"));
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Replayer stop (keeping actors)"));
|
||||
}
|
||||
}
|
||||
|
||||
bool CarlaReplayer::ReadHeader()
|
||||
{
|
||||
if (File.eof())
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
ReadValue<char>(File, Header.Id);
|
||||
ReadValue<uint32_t>(File, Header.Size);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void CarlaReplayer::SkipPacket(void)
|
||||
{
|
||||
File.seekg(Header.Size, std::ios::cur);
|
||||
}
|
||||
|
||||
void CarlaReplayer::Rewind(void)
|
||||
{
|
||||
CurrentTime = 0.0f;
|
||||
TotalTime = 0.0f;
|
||||
TimeToStop = 0.0f;
|
||||
|
||||
File.clear();
|
||||
File.seekg(0, std::ios::beg);
|
||||
|
||||
// mark as header as invalid to force reload a new one next time
|
||||
Frame.Elapsed = -1.0f;
|
||||
Frame.DurationThis = 0.0f;
|
||||
|
||||
MappedId.clear();
|
||||
|
||||
// read geneal Info
|
||||
RecInfo.Read(File);
|
||||
|
||||
// UE_LOG(LogCarla, Log, TEXT("Replayer rewind"));
|
||||
}
|
||||
|
||||
// read last frame in File and return the Total time recorded
|
||||
double CarlaReplayer::GetTotalTime(void)
|
||||
{
|
||||
std::streampos Current = File.tellg();
|
||||
|
||||
// parse only frames
|
||||
while (File)
|
||||
{
|
||||
// get header
|
||||
if (!ReadHeader())
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
// check for a frame packet
|
||||
switch (Header.Id)
|
||||
{
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameStart):
|
||||
Frame.Read(File);
|
||||
break;
|
||||
default:
|
||||
SkipPacket();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
File.clear();
|
||||
File.seekg(Current, std::ios::beg);
|
||||
return Frame.Elapsed;
|
||||
}
|
||||
|
||||
std::string CarlaReplayer::ReplayFile(std::string Filename, double TimeStart, double Duration, uint32_t ThisFollowId)
|
||||
{
|
||||
std::stringstream Info;
|
||||
std::string s;
|
||||
|
||||
// check to stop if we are replaying another
|
||||
if (Enabled)
|
||||
{
|
||||
Stop();
|
||||
}
|
||||
|
||||
Info << "Replaying File: " << Filename << std::endl;
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
// from start
|
||||
Rewind();
|
||||
|
||||
// get Total time of recorder
|
||||
TotalTime = GetTotalTime();
|
||||
Info << "Total time recorded: " << TotalTime << std::endl;
|
||||
// set time to start replayer
|
||||
if (TimeStart < 0.0f)
|
||||
{
|
||||
TimeStart = TotalTime + TimeStart;
|
||||
if (TimeStart < 0.0f)
|
||||
{
|
||||
TimeStart = 0.0f;
|
||||
}
|
||||
}
|
||||
// set time to stop replayer
|
||||
if (Duration > 0.0f)
|
||||
{
|
||||
TimeToStop = TimeStart + Duration;
|
||||
}
|
||||
else
|
||||
{
|
||||
TimeToStop = TotalTime;
|
||||
}
|
||||
Info << "Replaying from " << TimeStart << " s - " << TimeToStop << " s (" << TotalTime << " s)" <<
|
||||
std::endl;
|
||||
|
||||
// process all events until the time
|
||||
ProcessToTime(TimeStart);
|
||||
|
||||
// set the follow Id
|
||||
if (ThisFollowId != 0)
|
||||
FollowId = ThisFollowId;
|
||||
else
|
||||
FollowId = 0;
|
||||
|
||||
// mark as enabled
|
||||
Enabled = true;
|
||||
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessToTime(double Time)
|
||||
{
|
||||
double Per = 0.0f;
|
||||
double NewTime = CurrentTime + Time;
|
||||
bool bFrameFound = false;
|
||||
bool bExitAtNextFrame = false;
|
||||
bool bExitLoop = false;
|
||||
|
||||
// check if we are in the right frame
|
||||
if (NewTime >= Frame.Elapsed && NewTime < Frame.Elapsed + Frame.DurationThis)
|
||||
{
|
||||
Per = (NewTime - Frame.Elapsed) / Frame.DurationThis;
|
||||
bFrameFound = true;
|
||||
bExitLoop = true;
|
||||
// UE_LOG(LogCarla, Log, TEXT("Frame %f (%f) now %f per %f"), Frame.Elapsed, Frame.Elapsed + Frame.DurationThis, NewTime, Per);
|
||||
}
|
||||
|
||||
// process all frames until time we want or end
|
||||
while (!File.eof() && !bExitLoop)
|
||||
{
|
||||
// get header
|
||||
ReadHeader();
|
||||
|
||||
// check for a frame packet
|
||||
switch (Header.Id)
|
||||
{
|
||||
// frame
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameStart):
|
||||
// only read if we are not in the right frame
|
||||
Frame.Read(File);
|
||||
// check if target time is in this frame
|
||||
if (NewTime < Frame.Elapsed + Frame.DurationThis)
|
||||
{
|
||||
Per = (NewTime - Frame.Elapsed) / Frame.DurationThis;
|
||||
bFrameFound = true;
|
||||
// UE_LOG(LogCarla, Log, TEXT("Frame %f (%f) now %f per %f"), Frame.Elapsed, Frame.Elapsed + Frame.DurationThis, NewTime, Per);
|
||||
}
|
||||
break;
|
||||
|
||||
// events add
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventAdd):
|
||||
ProcessEventsAdd();
|
||||
break;
|
||||
|
||||
// events del
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventDel):
|
||||
ProcessEventsDel();
|
||||
break;
|
||||
|
||||
// events parent
|
||||
case static_cast<char>(CarlaRecorderPacketId::EventParent):
|
||||
ProcessEventsParent();
|
||||
break;
|
||||
|
||||
// collisions
|
||||
case static_cast<char>(CarlaRecorderPacketId::Collision):
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// positions
|
||||
case static_cast<char>(CarlaRecorderPacketId::Position):
|
||||
if (bFrameFound)
|
||||
ProcessPositions();
|
||||
else
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// states
|
||||
case static_cast<char>(CarlaRecorderPacketId::State):
|
||||
if (bFrameFound)
|
||||
ProcessStates();
|
||||
else
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
// frame end
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameEnd):
|
||||
if (bFrameFound)
|
||||
bExitLoop = true;
|
||||
break;
|
||||
|
||||
// unknown packet, just skip
|
||||
default:
|
||||
// skip packet
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
// update all positions
|
||||
if (Enabled && bFrameFound)
|
||||
{
|
||||
UpdatePositions(Per);
|
||||
}
|
||||
|
||||
// save current time
|
||||
CurrentTime = NewTime;
|
||||
|
||||
// stop replay?
|
||||
if (CurrentTime >= TimeToStop)
|
||||
{
|
||||
// check if we need to stop the replayer and let it continue in simulation
|
||||
// mode
|
||||
if (TimeToStop < TotalTime)
|
||||
{
|
||||
Stop(true); // keep actors in scene so they continue with AI
|
||||
}
|
||||
else
|
||||
{
|
||||
Stop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessEventsAdd(void)
|
||||
{
|
||||
uint16_t i, Total;
|
||||
CarlaRecorderEventAdd EventAdd;
|
||||
// std::stringstream Info;
|
||||
|
||||
// process creation events
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventAdd.Read(File);
|
||||
|
||||
// avoid sensor events
|
||||
if (!EventAdd.Description.Id.StartsWith("sensor."))
|
||||
{
|
||||
// show log
|
||||
/*
|
||||
Info.str("");
|
||||
Info << " Create " << EventAdd.DatabaseId << ": " << TCHAR_TO_UTF8(*EventAdd.Description.Id) << " (" <<
|
||||
EventAdd.Description.UId << ") at (" << EventAdd.Location.X << ", " <<
|
||||
EventAdd.Location.Y << ", " << EventAdd.Location.Z << ")" << std::endl;
|
||||
for (auto &Att : EventAdd.Description.Attributes)
|
||||
{
|
||||
Info << " " << TCHAR_TO_UTF8(*Att.Id) << " = " << TCHAR_TO_UTF8(*Att.Value) << std::endl;
|
||||
}
|
||||
|
||||
UE_LOG(LogCarla, Log, "%s", Info.str().c_str());
|
||||
*/
|
||||
|
||||
// auto Result = CallbackEventAdd(
|
||||
auto Result = Helper.ProcessReplayerEventAdd(
|
||||
EventAdd.Location,
|
||||
EventAdd.Rotation,
|
||||
std::move(EventAdd.Description),
|
||||
EventAdd.DatabaseId);
|
||||
|
||||
switch (Result.first)
|
||||
{
|
||||
// actor not created
|
||||
case 0:
|
||||
UE_LOG(LogCarla, Log, TEXT("actor could not be created"));
|
||||
break;
|
||||
|
||||
// actor created but with different id
|
||||
case 1:
|
||||
if (Result.second != EventAdd.DatabaseId)
|
||||
{
|
||||
// UE_LOG(LogCarla, Log, TEXT("actor created but with different id"));
|
||||
}
|
||||
// mapping id (recorded Id is a new Id in replayer)
|
||||
MappedId[EventAdd.DatabaseId] = Result.second;
|
||||
break;
|
||||
|
||||
// actor reused from existing
|
||||
case 2:
|
||||
// UE_LOG(LogCarla, Log, TEXT("actor already exist, not created"));
|
||||
// mapping id (say desired Id is mapped to what)
|
||||
MappedId[EventAdd.DatabaseId] = Result.second;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessEventsDel(void)
|
||||
{
|
||||
uint16_t i, Total;
|
||||
CarlaRecorderEventDel EventDel;
|
||||
// std::stringstream Info;
|
||||
|
||||
// process destroy events
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventDel.Read(File);
|
||||
// Info.str("");
|
||||
// Info << "Destroy " << MappedId[EventDel.DatabaseId] << "\n";
|
||||
// UE_LOG(LogCarla, Log, "%s", Info.str().c_str());
|
||||
Helper.ProcessReplayerEventDel(MappedId[EventDel.DatabaseId]);
|
||||
MappedId.erase(EventDel.DatabaseId);
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessEventsParent(void)
|
||||
{
|
||||
uint16_t i, Total;
|
||||
CarlaRecorderEventParent EventParent;
|
||||
std::stringstream Info;
|
||||
|
||||
// process parenting events
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventParent.Read(File);
|
||||
// Info.str("");
|
||||
// Info << "Parenting " << MappedId[EventParent.DatabaseId] << " with " << MappedId[EventParent.DatabaseId] <<
|
||||
// " (parent)\n";
|
||||
// UE_LOG(LogCarla, Log, "%s", Info.str().c_str());
|
||||
Helper.ProcessReplayerEventParent(MappedId[EventParent.DatabaseId], MappedId[EventParent.DatabaseIdParent]);
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessStates(void)
|
||||
{
|
||||
uint16_t i, Total;
|
||||
CarlaRecorderStateTrafficLight StateTrafficLight;
|
||||
std::stringstream Info;
|
||||
|
||||
// read Total traffic light states
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
StateTrafficLight.Read(File);
|
||||
|
||||
// UE_LOG(LogCarla, Log, TEXT("calling callback add"));
|
||||
StateTrafficLight.DatabaseId = MappedId[StateTrafficLight.DatabaseId];
|
||||
if (!Helper.ProcessReplayerStateTrafficLight(StateTrafficLight))
|
||||
{
|
||||
UE_LOG(LogCarla,
|
||||
Log,
|
||||
TEXT("callback state traffic light %d called but didn't work"),
|
||||
StateTrafficLight.DatabaseId);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessPositions(void)
|
||||
{
|
||||
uint16_t i, Total;
|
||||
|
||||
// save current as previous
|
||||
PrevPos = std::move(CurrPos);
|
||||
|
||||
// read all positions
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
CurrPos.clear();
|
||||
CurrPos.reserve(Total);
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
CarlaRecorderPosition Pos;
|
||||
Pos.Read(File);
|
||||
// assign mapped Id
|
||||
auto NewId = MappedId.find(Pos.DatabaseId);
|
||||
if (NewId != MappedId.end())
|
||||
{
|
||||
Pos.DatabaseId = NewId->second;
|
||||
}
|
||||
CurrPos.push_back(std::move(Pos));
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaReplayer::UpdatePositions(double Per)
|
||||
{
|
||||
unsigned int i;
|
||||
uint32_t NewFollowId = 0;
|
||||
std::unordered_map<int, int> TempMap;
|
||||
|
||||
// map the id of all previous positions to its index
|
||||
for (i = 0; i < PrevPos.size(); ++i)
|
||||
{
|
||||
TempMap[PrevPos[i].DatabaseId] = i;
|
||||
}
|
||||
|
||||
// get the Id of the actor to follow
|
||||
if (FollowId != 0)
|
||||
{
|
||||
auto NewId = MappedId.find(FollowId);
|
||||
if (NewId != MappedId.end())
|
||||
{
|
||||
NewFollowId = NewId->second;
|
||||
// UE_LOG(LogCarla, Log, TEXT("Following %d (%d)"), NewFollowId, FollowId);
|
||||
}
|
||||
}
|
||||
|
||||
// go through each actor and update
|
||||
for (i = 0; i < CurrPos.size(); ++i)
|
||||
{
|
||||
// check if exist a previous position
|
||||
auto Result = TempMap.find(CurrPos[i].DatabaseId);
|
||||
if (Result != TempMap.end())
|
||||
{
|
||||
// interpolate
|
||||
InterpolatePosition(PrevPos[Result->second], CurrPos[i], Per);
|
||||
}
|
||||
else
|
||||
{
|
||||
// assign last position (we don't have previous one)
|
||||
InterpolatePosition(CurrPos[i], CurrPos[i], 0);
|
||||
}
|
||||
|
||||
// move the camera to follow this actor if required
|
||||
if (NewFollowId != 0)
|
||||
{
|
||||
if (NewFollowId == CurrPos[i].DatabaseId)
|
||||
Helper.SetCameraPosition(NewFollowId, FVector(-1000, 0, 500), FQuat::MakeFromEuler({0, -25, 0}));
|
||||
// Helper.SetCameraPosition(NewFollowId, FVector(0, 0, 2000), FQuat::MakeFromEuler({0, -70, 0}));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// interpolate a position (transform, velocity...)
|
||||
void CarlaReplayer::InterpolatePosition(
|
||||
const CarlaRecorderPosition &Pos1,
|
||||
const CarlaRecorderPosition &Pos2,
|
||||
double Per)
|
||||
{
|
||||
// call the callback
|
||||
Helper.ProcessReplayerPosition(Pos1, Pos2, Per);
|
||||
}
|
||||
|
||||
// tick for the replayer
|
||||
void CarlaReplayer::Tick(float Delta)
|
||||
{
|
||||
// check if there are events to process
|
||||
if (Enabled)
|
||||
{
|
||||
ProcessToTime(Delta);
|
||||
}
|
||||
|
||||
// UE_LOG(LogCarla, Log, TEXT("Replayer tick"));
|
||||
}
|
|
@ -0,0 +1,114 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <fstream>
|
||||
#include <sstream>
|
||||
#include <unordered_map>
|
||||
|
||||
#include <functional>
|
||||
#include "CarlaRecorderInfo.h"
|
||||
#include "CarlaRecorderFrames.h"
|
||||
#include "CarlaRecorderEventAdd.h"
|
||||
#include "CarlaRecorderEventDel.h"
|
||||
#include "CarlaRecorderEventParent.h"
|
||||
#include "CarlaRecorderCollision.h"
|
||||
#include "CarlaRecorderPosition.h"
|
||||
#include "CarlaRecorderState.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
#include "CarlaReplayerHelper.h"
|
||||
|
||||
class UCarlaEpisode;
|
||||
|
||||
class CarlaReplayer
|
||||
{
|
||||
#pragma pack(push, 1)
|
||||
struct Header
|
||||
{
|
||||
char Id;
|
||||
uint32_t Size;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
public:
|
||||
|
||||
CarlaReplayer() {};
|
||||
~CarlaReplayer() { Stop(); };
|
||||
|
||||
std::string ReplayFile(std::string Filename, double TimeStart = 0.0f, double Duration = 0.0f, uint32_t FollowId = 0);
|
||||
|
||||
// void Start(void);
|
||||
void Stop(bool KeepActors = false);
|
||||
|
||||
void Enable(void);
|
||||
|
||||
void Disable(void);
|
||||
|
||||
bool IsEnabled(void)
|
||||
{
|
||||
return Enabled;
|
||||
}
|
||||
|
||||
// set episode
|
||||
void SetEpisode(UCarlaEpisode *ThisEpisode)
|
||||
{
|
||||
Episode = ThisEpisode;
|
||||
Helper.SetEpisode(ThisEpisode);
|
||||
}
|
||||
|
||||
// tick for the replayer
|
||||
void Tick(float Time);
|
||||
|
||||
private:
|
||||
|
||||
bool Enabled;
|
||||
UCarlaEpisode *Episode = nullptr;
|
||||
// binary file reader
|
||||
std::ifstream File;
|
||||
Header Header;
|
||||
CarlaRecorderInfo RecInfo;
|
||||
CarlaRecorderFrame Frame;
|
||||
// positions (to be able to interpolate)
|
||||
std::vector<CarlaRecorderPosition> CurrPos;
|
||||
std::vector<CarlaRecorderPosition> PrevPos;
|
||||
// mapping id
|
||||
std::unordered_map<uint32_t, uint32_t> MappedId;
|
||||
// times
|
||||
double CurrentTime;
|
||||
double TimeToStop;
|
||||
double TotalTime;
|
||||
// helper
|
||||
CarlaReplayerHelper Helper;
|
||||
// follow camera
|
||||
uint32_t FollowId;
|
||||
|
||||
// utils
|
||||
bool ReadHeader();
|
||||
|
||||
void SkipPacket();
|
||||
|
||||
double GetTotalTime(void);
|
||||
|
||||
void Rewind(void);
|
||||
|
||||
// processing packets
|
||||
void ProcessToTime(double Time);
|
||||
|
||||
void ProcessEventsAdd(void);
|
||||
void ProcessEventsDel(void);
|
||||
void ProcessEventsParent(void);
|
||||
|
||||
void ProcessPositions(void);
|
||||
|
||||
void ProcessStates(void);
|
||||
|
||||
// positions
|
||||
void UpdatePositions(double Per);
|
||||
|
||||
void InterpolatePosition(const CarlaRecorderPosition &Start, const CarlaRecorderPosition &End, double Per);
|
||||
|
||||
};
|
|
@ -0,0 +1,316 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#include "CarlaReplayerHelper.h"
|
||||
#include "Carla/Actor/ActorView.h"
|
||||
#include "Carla/Actor/ActorDescription.h"
|
||||
|
||||
// create or reuse an actor for replaying
|
||||
std::pair<int, FActorView &>CarlaReplayerHelper::TryToCreateReplayerActor(
|
||||
FVector &Location,
|
||||
FVector &Rotation,
|
||||
FActorDescription &ActorDesc,
|
||||
uint32_t DesiredId)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
|
||||
FActorView view_empty;
|
||||
|
||||
// check type of actor we need
|
||||
if (ActorDesc.Id.StartsWith("traffic."))
|
||||
{
|
||||
AActor *Actor = FindTrafficLightAt(Location);
|
||||
if (Actor != nullptr)
|
||||
{
|
||||
// actor found
|
||||
auto view = Episode->GetActorRegistry().Find(Actor);
|
||||
// reuse that actor
|
||||
// UE_LOG(LogCarla, Log, TEXT("TrafficLight found with id: %d"), view.GetActorId());
|
||||
return std::pair<int, FActorView &>(2, view);
|
||||
}
|
||||
else
|
||||
{
|
||||
// actor not found
|
||||
UE_LOG(LogCarla, Log, TEXT("TrafficLight not found"));
|
||||
return std::pair<int, FActorView &>(0, view_empty);
|
||||
}
|
||||
}
|
||||
else if (!ActorDesc.Id.StartsWith("sensor."))
|
||||
{
|
||||
// check if an actor of that type already exist with same id
|
||||
// UE_LOG(LogCarla, Log, TEXT("Trying to create actor: %s (%d)"), *ActorDesc.Id, DesiredId);
|
||||
if (Episode->GetActorRegistry().Contains(DesiredId))
|
||||
{
|
||||
auto view = Episode->GetActorRegistry().Find(DesiredId);
|
||||
const FActorDescription *desc = &view.GetActorInfo()->Description;
|
||||
// UE_LOG(LogCarla, Log, TEXT("actor '%s' already exist with id %d"), *(desc->Id), view.GetActorId());
|
||||
if (desc->Id == ActorDesc.Id)
|
||||
{
|
||||
// we don't need to create, actor of same type already exist
|
||||
return std::pair<int, FActorView &>(2, view);
|
||||
}
|
||||
}
|
||||
// create the transform
|
||||
FRotator Rot = FRotator::MakeFromEuler(Rotation);
|
||||
// FTransform Trans(Rot, Location, FVector(1, 1, 1));
|
||||
FTransform Trans(Rot, FVector(0, 0, 100000), FVector(1, 1, 1));
|
||||
// create as new actor
|
||||
TPair<EActorSpawnResultStatus, FActorView> Result = Episode->SpawnActorWithInfo(Trans, ActorDesc, DesiredId);
|
||||
if (Result.Key == EActorSpawnResultStatus::Success)
|
||||
{
|
||||
// UE_LOG(LogCarla, Log, TEXT("Actor created by replayer with id %d"), Result.Value.GetActorId());
|
||||
// relocate
|
||||
FTransform Trans2(Rot, Location, FVector(1, 1, 1));
|
||||
Result.Value.GetActor()->SetActorTransform(Trans2, false, nullptr, ETeleportType::TeleportPhysics);
|
||||
// Result.Value.GetActor()->SetLocation(Trans2);
|
||||
return std::pair<int, FActorView &>(1, Result.Value);
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Actor could't be created by replayer"));
|
||||
return std::pair<int, FActorView &>(0, Result.Value);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// actor ignored
|
||||
return std::pair<int, FActorView &>(0, view_empty);
|
||||
}
|
||||
}
|
||||
|
||||
AActor *CarlaReplayerHelper::FindTrafficLightAt(FVector Location)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
auto World = Episode->GetWorld();
|
||||
check(World != nullptr);
|
||||
|
||||
// get its position (truncated as int's)
|
||||
int x = static_cast<int>(Location.X);
|
||||
int y = static_cast<int>(Location.Y);
|
||||
int z = static_cast<int>(Location.Z);
|
||||
// UE_LOG(LogCarla, Log, TEXT("Trying to find traffic: [%d,%d,%d]"), x, y, z);
|
||||
|
||||
// search an "traffic." actor at that position
|
||||
for (TActorIterator<ATrafficSignBase> It(World); It; ++It)
|
||||
{
|
||||
ATrafficSignBase *Actor = *It;
|
||||
check(Actor != nullptr);
|
||||
FVector vec = Actor->GetTransform().GetTranslation();
|
||||
int x2 = static_cast<int>(vec.X);
|
||||
int y2 = static_cast<int>(vec.Y);
|
||||
int z2 = static_cast<int>(vec.Z);
|
||||
// UE_LOG(LogCarla, Log, TEXT(" Checking with [%d,%d,%d]"), x2, y2, z2);
|
||||
if ((x2 == x) && (y2 == y) && (z2 == z))
|
||||
{
|
||||
// actor found
|
||||
return static_cast<AActor *>(Actor);
|
||||
}
|
||||
}
|
||||
// actor not found
|
||||
return nullptr;
|
||||
}
|
||||
|
||||
// enable / disable physics for an actor
|
||||
bool CarlaReplayerHelper::SetActorSimulatePhysics(FActorView &ActorView, bool bEnabled)
|
||||
{
|
||||
if (!ActorView.IsValid())
|
||||
{
|
||||
return false;
|
||||
}
|
||||
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
|
||||
if (RootComponent == nullptr)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
RootComponent->SetSimulatePhysics(bEnabled);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// enable / disable autopilot for an actor
|
||||
bool CarlaReplayerHelper::SetActorAutopilot(FActorView &ActorView, bool bEnabled)
|
||||
{
|
||||
if (!ActorView.IsValid())
|
||||
{
|
||||
return false;
|
||||
}
|
||||
auto Vehicle = Cast<ACarlaWheeledVehicle>(ActorView.GetActor());
|
||||
if (Vehicle == nullptr)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController());
|
||||
if (Controller == nullptr)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
Controller->SetAutopilot(bEnabled);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
// replay event for creating actor
|
||||
std::pair<int, uint32_t> CarlaReplayerHelper::ProcessReplayerEventAdd(
|
||||
FVector Location,
|
||||
FVector Rotation,
|
||||
CarlaRecorderActorDescription Description,
|
||||
uint32_t DesiredId)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
FActorDescription ActorDesc;
|
||||
|
||||
// prepare actor description
|
||||
ActorDesc.UId = Description.UId;
|
||||
ActorDesc.Id = Description.Id;
|
||||
for (const auto &Item : Description.Attributes)
|
||||
{
|
||||
FActorAttribute Attr;
|
||||
Attr.Type = static_cast<EActorAttributeType>(Item.Type);
|
||||
Attr.Id = Item.Id;
|
||||
Attr.Value = Item.Value;
|
||||
ActorDesc.Variations.Add(Attr.Id, std::move(Attr));
|
||||
}
|
||||
|
||||
auto result = TryToCreateReplayerActor(Location, Rotation, ActorDesc, DesiredId);
|
||||
|
||||
if (result.first != 0)
|
||||
{
|
||||
// disable physics
|
||||
// SetActorSimulatePhysics(result.second, false);
|
||||
// disable autopilot
|
||||
SetActorAutopilot(result.second, false);
|
||||
}
|
||||
|
||||
return std::make_pair(result.first, result.second.GetActorId());
|
||||
}
|
||||
|
||||
// replay event for removing actor
|
||||
bool CarlaReplayerHelper::ProcessReplayerEventDel(uint32_t DatabaseId)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
auto actor = Episode->GetActorRegistry().Find(DatabaseId).GetActor();
|
||||
if (actor == nullptr)
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Actor %d not found to destroy"), DatabaseId);
|
||||
return false;
|
||||
}
|
||||
Episode->DestroyActor(actor);
|
||||
return true;
|
||||
}
|
||||
|
||||
// replay event for parenting actors
|
||||
bool CarlaReplayerHelper::ProcessReplayerEventParent(uint32_t ChildId, uint32_t ParentId)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
AActor *child = Episode->GetActorRegistry().Find(ChildId).GetActor();
|
||||
AActor *parent = Episode->GetActorRegistry().Find(ParentId).GetActor();
|
||||
if (child && parent)
|
||||
{
|
||||
child->AttachToActor(parent, FAttachmentTransformRules::KeepRelativeTransform);
|
||||
child->SetOwner(parent);
|
||||
// UE_LOG(LogCarla, Log, TEXT("Parenting Actor"));
|
||||
return true;
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Parenting Actors not found"));
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// reposition actors
|
||||
bool CarlaReplayerHelper::ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
AActor *Actor = Episode->GetActorRegistry().Find(Pos1.DatabaseId).GetActor();
|
||||
if (Actor && !Actor->IsPendingKill())
|
||||
{
|
||||
// interpolate transform
|
||||
FVector Location = FMath::Lerp(FVector(Pos1.Location), FVector(Pos2.Location), Per);
|
||||
FRotator Rotation = FMath::Lerp(FRotator::MakeFromEuler(Pos1.Rotation), FRotator::MakeFromEuler(Pos2.Rotation), Per);
|
||||
FTransform Trans(Rotation, Location, FVector(1, 1, 1));
|
||||
Actor->SetActorTransform(Trans, false, nullptr, ETeleportType::TeleportPhysics);
|
||||
// reset velocities
|
||||
ResetVelocities(Actor);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// reset velocity vectors on actor
|
||||
void CarlaReplayerHelper::ResetVelocities(AActor *Actor)
|
||||
{
|
||||
if (Actor && !Actor->IsPendingKill())
|
||||
{
|
||||
auto RootComponent = Cast<UPrimitiveComponent>(Actor->GetRootComponent());
|
||||
if (RootComponent != nullptr)
|
||||
{
|
||||
FVector Vector(0, 0, 0);
|
||||
// reset velocities
|
||||
RootComponent->SetPhysicsLinearVelocity(Vector, false, "None");
|
||||
RootComponent->SetPhysicsAngularVelocityInDegrees(Vector, false, "None");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// reposition the camera
|
||||
bool CarlaReplayerHelper::SetCameraPosition(uint32_t Id, FVector Offset, FQuat Rotation)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
|
||||
// get specator pawn
|
||||
APawn *Spectator = Episode->GetSpectatorPawn();
|
||||
// get the actor to follow
|
||||
AActor *Actor = Episode->FindActor(Id).GetActor();
|
||||
|
||||
// check
|
||||
if (!Spectator || !Actor)
|
||||
return false;
|
||||
|
||||
// set the new position
|
||||
FQuat ActorRot = Actor->GetActorTransform().GetRotation();
|
||||
FVector Pos = Actor->GetActorTransform().GetTranslation() + (ActorRot.RotateVector(Offset));
|
||||
Spectator->SetActorLocation(Pos);
|
||||
Spectator->SetActorRotation(ActorRot * Rotation);
|
||||
|
||||
// UE_LOG(LogCarla, Log, TEXT("Set camera at [%d,%d,%d]"), Pos.X, Pos.Y, Pos.Z);
|
||||
return true;
|
||||
}
|
||||
|
||||
bool CarlaReplayerHelper::ProcessReplayerStateTrafficLight(CarlaRecorderStateTrafficLight State)
|
||||
{
|
||||
check(Episode != nullptr);
|
||||
AActor *Actor = Episode->GetActorRegistry().Find(State.DatabaseId).GetActor();
|
||||
if (Actor && !Actor->IsPendingKill())
|
||||
{
|
||||
auto TrafficLight = Cast<ATrafficLightBase>(Actor);
|
||||
if (TrafficLight != nullptr)
|
||||
{
|
||||
TrafficLight->SetTrafficLightState(static_cast<ETrafficLightState>(State.State));
|
||||
TrafficLight->SetTimeIsFrozen(State.IsFrozen);
|
||||
TrafficLight->SetElapsedTime(State.ElapsedTime);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
// replay finish
|
||||
bool CarlaReplayerHelper::ProcessReplayerFinish(bool bApplyAutopilot)
|
||||
{
|
||||
if (!bApplyAutopilot)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
// set autopilot to all AI vehicles
|
||||
auto registry = Episode->GetActorRegistry();
|
||||
for (auto &&ActorView : registry)
|
||||
{
|
||||
SetActorAutopilot(ActorView, true);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
|
@ -0,0 +1,68 @@
|
|||
// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma
|
||||
// de Barcelona (UAB).
|
||||
//
|
||||
// This work is licensed under the terms of the MIT license.
|
||||
// For a copy, see <https://opensource.org/licenses/MIT>.
|
||||
|
||||
#pragma once
|
||||
|
||||
class UCarlaEpisode;
|
||||
class FActorView;
|
||||
struct FActorDescription;
|
||||
|
||||
class CarlaReplayerHelper
|
||||
{
|
||||
|
||||
public:
|
||||
|
||||
// set the episode to use
|
||||
void SetEpisode(UCarlaEpisode *ThisEpisode)
|
||||
{
|
||||
Episode = ThisEpisode;
|
||||
}
|
||||
|
||||
// replay event for creating actor
|
||||
std::pair<int, uint32_t> ProcessReplayerEventAdd(
|
||||
FVector Location,
|
||||
FVector Rotation,
|
||||
CarlaRecorderActorDescription Description,
|
||||
uint32_t DesiredId);
|
||||
|
||||
// replay event for removing actor
|
||||
bool ProcessReplayerEventDel(uint32_t DatabaseId);
|
||||
|
||||
// replay event for parenting actors
|
||||
bool ProcessReplayerEventParent(uint32_t ChildId, uint32_t ParentId);
|
||||
|
||||
// reposition actors
|
||||
bool ProcessReplayerPosition(CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2, double Per);
|
||||
|
||||
// replay event for traffic light state
|
||||
bool ProcessReplayerStateTrafficLight(CarlaRecorderStateTrafficLight State);
|
||||
|
||||
// replay finish
|
||||
bool ProcessReplayerFinish(bool bApplyAutopilot);
|
||||
|
||||
// set the camera position to follow an actor
|
||||
bool SetCameraPosition(uint32_t Id, FVector Offset, FQuat Rotation);
|
||||
|
||||
private:
|
||||
|
||||
UCarlaEpisode *Episode {nullptr};
|
||||
|
||||
std::pair<int, FActorView &>TryToCreateReplayerActor(
|
||||
FVector &Location,
|
||||
FVector &Rotation,
|
||||
FActorDescription &ActorDesc,
|
||||
uint32_t DesiredId);
|
||||
|
||||
AActor *FindTrafficLightAt(FVector Location);
|
||||
|
||||
// enable / disable physics for an actor
|
||||
bool SetActorSimulatePhysics(FActorView &ActorView, bool bEnabled);
|
||||
// enable / disable autopilot for an actor
|
||||
bool SetActorAutopilot(FActorView &ActorView, bool bEnabled);
|
||||
// reset velocity vectors on actor
|
||||
void ResetVelocities(AActor *Actor);
|
||||
|
||||
};
|
|
@ -67,5 +67,8 @@ void ACollisionSensor::OnCollisionEvent(
|
|||
Episode->SerializeActor(Episode->FindOrFakeActor(Actor)),
|
||||
Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)),
|
||||
carla::geom::Vector3D{NormalImpulse.X, NormalImpulse.Y, NormalImpulse.Z});
|
||||
// record the collision event
|
||||
if (Episode->GetRecorder()->IsEnabled())
|
||||
Episode->GetRecorder()->AddCollision(Actor, OtherActor);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -82,7 +82,8 @@ static carla::Buffer AWorldObserver_Serialize(
|
|||
carla::Buffer buffer,
|
||||
double game_timestamp,
|
||||
double platform_timestamp,
|
||||
const FActorRegistry &Registry)
|
||||
const FActorRegistry &Registry
|
||||
)
|
||||
{
|
||||
using Serializer = carla::sensor::s11n::EpisodeStateSerializer;
|
||||
using ActorDynamicState = carla::sensor::data::ActorDynamicState;
|
||||
|
@ -146,6 +147,8 @@ void AWorldObserver::Tick(float DeltaSeconds)
|
|||
AsyncStream.PopBufferFromPool(),
|
||||
GameTimeStamp,
|
||||
FPlatformTime::Seconds(),
|
||||
Episode->GetActorRegistry());
|
||||
Episode->GetActorRegistry()
|
||||
);
|
||||
|
||||
AsyncStream.Send(*this, std::move(buffer));
|
||||
}
|
||||
|
|
|
@ -22,6 +22,7 @@
|
|||
#include <carla/rpc/MapInfo.h>
|
||||
#include <carla/rpc/Response.h>
|
||||
#include <carla/rpc/Server.h>
|
||||
#include <carla/rpc/String.h>
|
||||
#include <carla/rpc/Transform.h>
|
||||
#include <carla/rpc/Vector2D.h>
|
||||
#include <carla/rpc/Vector3D.h>
|
||||
|
@ -589,6 +590,52 @@ void FTheNewCarlaServer::FPimpl::BindActions()
|
|||
return R<void>::Success();
|
||||
});
|
||||
|
||||
Server.BindSync("start_recorder", [this](std::string name) -> R<std::string> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->StartRecorder(name));
|
||||
});
|
||||
|
||||
Server.BindSync("stop_recorder", [this]() -> R<void> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
Episode->GetRecorder()->Stop();
|
||||
return R<void>::Success();
|
||||
});
|
||||
|
||||
Server.BindSync("show_recorder_file_info", [this](std::string name) -> R<std::string> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder()->ShowFileInfo(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name));
|
||||
});
|
||||
|
||||
Server.BindSync("show_recorder_collisions", [this](std::string name, char type1, char type2) -> R<std::string> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder()->ShowFileCollisions(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name,
|
||||
type1,
|
||||
type2));
|
||||
});
|
||||
|
||||
Server.BindSync("show_recorder_actors_blocked", [this](std::string name, double min_time, double min_distance) -> R<std::string> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder()->ShowFileActorsBlocked(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name,
|
||||
min_time,
|
||||
min_distance));
|
||||
});
|
||||
|
||||
Server.BindSync("replay_file", [this](std::string name, double start, double duration, uint32_t follow_id) -> R<std::string> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder()->ReplayFile(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name,
|
||||
start,
|
||||
duration,
|
||||
follow_id));
|
||||
});
|
||||
|
||||
Server.BindSync("get_group_traffic_lights", [this](
|
||||
const cr::Actor Actor) -> R<std::vector<cr::actor_id_type>>
|
||||
{
|
||||
|
|
|
@ -196,6 +196,11 @@ float ATrafficLightBase::GetElapsedTime() const
|
|||
return ElapsedTime;
|
||||
}
|
||||
|
||||
void ATrafficLightBase::SetElapsedTime(float InElapsedTime)
|
||||
{
|
||||
ElapsedTime = InElapsedTime;
|
||||
}
|
||||
|
||||
void ATrafficLightBase::SetTimeIsFrozen(bool InTimeIsFrozen)
|
||||
{
|
||||
TimeIsFrozen = InTimeIsFrozen;
|
||||
|
|
|
@ -93,6 +93,9 @@ public:
|
|||
UFUNCTION(Category = "Traffic Light", BlueprintCallable)
|
||||
void SetGroupTrafficLights(TArray<ATrafficLightBase *> InGroupTrafficLights);
|
||||
|
||||
// used from replayer
|
||||
void SetElapsedTime(float InElapsedTime);
|
||||
|
||||
protected:
|
||||
|
||||
UFUNCTION(Category = "Traffic Light", BlueprintImplementableEvent)
|
||||
|
|
|
@ -22,8 +22,9 @@ USAGE_STRING="Usage: $0 [-h|--help] [-d|--dir] <outdir> [-f|--file] <filename>"
|
|||
|
||||
OUTPUT_DIRECTORY=""
|
||||
FILE_NAME=""
|
||||
MAP_PATH=""
|
||||
|
||||
OPTS=`getopt -o h,d::,f --long help,dir::,file:: -n 'parse-options' -- "$@"`
|
||||
OPTS=`getopt -o h --long help,dir:,file:,map: -n 'parse-options' -- "$@"`
|
||||
|
||||
if [ $? != 0 ] ; then echo "$USAGE_STRING" ; exit 2; fi
|
||||
|
||||
|
@ -33,10 +34,13 @@ while true; do
|
|||
case "$1" in
|
||||
--dir )
|
||||
OUTPUT_DIRECTORY="$2"
|
||||
shift ;;
|
||||
shift 2;;
|
||||
--file )
|
||||
FILE_NAME="$2"
|
||||
shift ;;
|
||||
shift 2;;
|
||||
--map )
|
||||
MAP_PATH="$2"
|
||||
shift 2;;
|
||||
-h | --help )
|
||||
echo "$DOC_STRING"
|
||||
echo "$USAGE_STRING"
|
||||
|
@ -54,6 +58,8 @@ if [ -z "${FILE_NAME}" ]; then
|
|||
FILE_NAME="CookedExportedMaps"
|
||||
fi
|
||||
|
||||
|
||||
|
||||
# ==============================================================================
|
||||
# -- Package project -----------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
@ -64,7 +70,7 @@ BUILD_FOLDER=${OUTPUT_DIRECTORY}
|
|||
|
||||
log "Packaging user content from version '$REPOSITORY_TAG'."
|
||||
|
||||
rm -Rf ${BUILD_FOLDER}
|
||||
#rm -Rf ${BUILD_FOLDER}
|
||||
mkdir -p ${BUILD_FOLDER}
|
||||
|
||||
pushd "${CARLAUE4_ROOT_FOLDER}" > /dev/null
|
||||
|
@ -72,54 +78,45 @@ pushd "${CARLAUE4_ROOT_FOLDER}" > /dev/null
|
|||
log "Current project directory: '${PWD}'"
|
||||
|
||||
MAP_LIST=""
|
||||
|
||||
for filepath in `find ${PWD}/Content/ -type f -name "*.umap"`; do
|
||||
if [[ $filepath == *"/ExportedMaps/"* ]]; then
|
||||
filepath="/Game/"${filepath#"${PWD}/Content/"}
|
||||
if [ -z "${MAP_LIST}" ]; then
|
||||
MAP_LIST=$filepath
|
||||
else
|
||||
MAP_LIST=$MAP_LIST+$filepath
|
||||
if [ -z "${MAP_PATH}" ]; then
|
||||
for filepath in `find ${PWD}/Content/ -type f -name "*.umap"`; do
|
||||
if [[ $filepath == *"/ExportedMaps/"* ]]; then
|
||||
filepath="/Game/"${filepath#"${PWD}/Content/"}
|
||||
if [ -z "${MAP_LIST}" ]; then
|
||||
MAP_LIST=$filepath
|
||||
else
|
||||
MAP_LIST=$MAP_LIST+$filepath
|
||||
fi
|
||||
fi
|
||||
fi
|
||||
done
|
||||
done
|
||||
else
|
||||
MAP_LIST=${MAP_PATH}
|
||||
fi
|
||||
|
||||
${UE4_ROOT}/Engine/Binaries/Linux/UE4Editor "${PWD}/CarlaUE4.uproject" -run=cook -map=${MAP_LIST} -cooksinglepackage -targetplatform="LinuxNoEditor" -OutputDir="${BUILD_FOLDER}/Cooked"
|
||||
|
||||
echo $MAP_LIST
|
||||
${UE4_ROOT}/Engine/Build/BatchFiles/RunUAT.sh BuildCookRun \
|
||||
-project="${PWD}/CarlaUE4.uproject" -map=$MAP_LIST \
|
||||
-nocompileeditor -nop4 -cook \
|
||||
-archive -package -stage -nodebuginfo -build \
|
||||
-clientconfig=Development -ue4exe=UE4Editor \
|
||||
-targetplatform=Linux -CrashReporter -utf8output \
|
||||
-SkipCookingEditorContent -archivedirectory="${BUILD_FOLDER}"
|
||||
|
||||
popd >/dev/null
|
||||
|
||||
if [[ ! -d ${BUILD_FOLDER}/LinuxNoEditor ]] ; then
|
||||
fatal_error "Failed to package the project!"
|
||||
fi
|
||||
#if [[ ! -d ${BUILD_FOLDER}/LinuxNoEditor ]] ; then
|
||||
# fatal_error "Failed to package the project!"
|
||||
#fi
|
||||
|
||||
# ==============================================================================
|
||||
# -- Zip the project -----------------------------------------------------------
|
||||
# ==============================================================================
|
||||
|
||||
DESTINATION=${BUILD_FOLDER}/${FILE_NAME}.tar.gz
|
||||
SOURCE=${BUILD_FOLDER}
|
||||
SOURCE=${BUILD_FOLDER}/Cooked
|
||||
|
||||
pushd "${SOURCE}/LinuxNoEditor" >/dev/null
|
||||
pushd "${SOURCE}" >/dev/null
|
||||
|
||||
log "Packaging build."
|
||||
|
||||
rm -Rf ./CarlaUE4/Saved
|
||||
rm -Rf ./Engine
|
||||
rm ./CarlaUE4.sh
|
||||
rm ./Manifest_NonUFSFiles_Linux.txt
|
||||
rm ./Manifest_UFSFiles_Linux.txt
|
||||
rm -Rf ./CarlaUE4/Binaries
|
||||
rm -Rf ./CarlaUE4/Config
|
||||
#rm -Rf ./Engine
|
||||
rm -Rf ./CarlaUE4/Metadata
|
||||
rm -Rf ./CarlaUE4/Plugins
|
||||
rm ./CarlaUE4/AssetRegistry.bin
|
||||
rm ./CarlaUE4/CarlaUE4.uproject
|
||||
|
||||
tar -czvf ${DESTINATION} *
|
||||
|
||||
|
@ -132,7 +129,7 @@ popd > /dev/null
|
|||
|
||||
log "Removing intermediate build."
|
||||
|
||||
rm -Rf ${BUILD_FOLDER}/LinuxNoEditor
|
||||
rm -Rf ${BUILD_FOLDER}/Cooked
|
||||
|
||||
# ==============================================================================
|
||||
# -- ...and we are done --------------------------------------------------------
|
||||
|
|
|
@ -17,4 +17,4 @@
|
|||
0.9.1: 1IZDzNQNVL67h8UlGyKuGegLH612Ifd7H
|
||||
0.9.2: 1RKRGB22U5t80q4zwYXBJvxQXhzNjaaDf
|
||||
0.9.3: 1jJlStNHpey62CrMkWVfmtQcJGO7PaD0R
|
||||
Latest: 1LA1dLOozATCaJryqT7U_nOBR_nPVnBC8
|
||||
Latest: 1jSrhk8yTk_bS1UVAZfkIqtlAJ3lCoI9b
|
||||
|
|
|
@ -21,6 +21,7 @@ pages:
|
|||
- 'Running in a Docker': 'carla_docker.md'
|
||||
- "How to make a new map with RoadRunner": 'how_to_make_a_new_map.md'
|
||||
- "How to link Epic's Automotive Materials": 'epic_automotive_materials.md'
|
||||
- "How to automatically generate a map from RoadRunner": 'generate_map_from_fbx.md'
|
||||
- "How to export and import maps to distribution builds": 'export_import_dist.md'
|
||||
- Contributing:
|
||||
- 'Contribution guidelines': 'CONTRIBUTING.md'
|
||||
|
|
Loading…
Reference in New Issue