Merge pull request #1364 from carla-simulator/bernatx/Recorder
Bernatx/recorder
This commit is contained in:
commit
2419533bca
|
@ -1,3 +1,10 @@
|
|||
## Latest
|
||||
|
||||
* New recorder features:
|
||||
- Added optional parameter to show more details about a recorder file (related to `show_recorder_file_info.py`)
|
||||
- Added playback speed (slow/fast motion) for the replayer
|
||||
- We can use an absolute path for the recorded files (to choose where to 'write to' or 'read from')
|
||||
|
||||
## CARLA 0.9.5
|
||||
|
||||
* New Town07, rural environment with narrow roads
|
||||
|
|
|
@ -20,6 +20,7 @@
|
|||
- `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)`
|
||||
- `set_replayer_speed(float time_factor)`
|
||||
- `apply_batch(commands, do_tick=False)`
|
||||
- `apply_batch_sync(commands, do_tick=False) -> list(carla.command.Response)`
|
||||
|
||||
|
|
|
@ -415,7 +415,9 @@ converted to OpenDrive format, and saved to disk as such.
|
|||
|
||||
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.
|
||||
All data is written in a binary file on the server. We can use filenames with or without a path. If we specify a filename without any of '\\', '/' or ':' characters, then it is considered to be only a filename and will be saved on folder **CarlaUE4/Saved**. If we use any of the previous characters then the filename will be considered as an absolute filename with path (for example: '/home/carla/recording01.log' or 'c:\\records\\recording01.log').
|
||||
|
||||
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:
|
||||
|
||||
|
@ -449,6 +451,16 @@ client.replay_file("recording01.log", start, duration, camera)
|
|||
* **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 specify the time factor (speed) for the replayer at any moment, using the next API:
|
||||
|
||||
```py
|
||||
client.set_replayer_time_factor(2.0)
|
||||
```
|
||||
A value greater than 1.0 will play in fast motion, and a value below 1.0 will play in slow motion, being 1.0 the default value for normal playback.
|
||||
As a performance trick, with values over 2.0 the interpolation of positions is disabled.
|
||||
|
||||
The call of this API will not stop the replayer in course, it will change just the speed, so you can change that several times while the replayer is running.
|
||||
|
||||
We can know details about a recorded simulation, using this API:
|
||||
|
||||
```py
|
||||
|
|
|
@ -68,8 +68,8 @@ namespace client {
|
|||
_simulator->StopRecorder();
|
||||
}
|
||||
|
||||
std::string ShowRecorderFileInfo(std::string name) {
|
||||
return _simulator->ShowRecorderFileInfo(name);
|
||||
std::string ShowRecorderFileInfo(std::string name, bool show_all) {
|
||||
return _simulator->ShowRecorderFileInfo(name, show_all);
|
||||
}
|
||||
|
||||
std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
|
||||
|
@ -84,6 +84,10 @@ namespace client {
|
|||
return _simulator->ReplayFile(name, start, duration, follow_id);
|
||||
}
|
||||
|
||||
void SetReplayerTimeFactor(double time_factor) {
|
||||
_simulator->SetReplayerTimeFactor(time_factor);
|
||||
}
|
||||
|
||||
void ApplyBatch(
|
||||
std::vector<rpc::Command> commands,
|
||||
bool do_tick_cue = false) const {
|
||||
|
|
|
@ -275,8 +275,8 @@ namespace detail {
|
|||
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::ShowRecorderFileInfo(std::string name, bool show_all) {
|
||||
return _pimpl->CallAndWait<std::string>("show_recorder_file_info", name, show_all);
|
||||
}
|
||||
|
||||
std::string Client::ShowRecorderCollisions(std::string name, char type1, char type2) {
|
||||
|
@ -291,6 +291,10 @@ namespace detail {
|
|||
return _pimpl->CallAndWait<std::string>("replay_file", name, start, duration, follow_id);
|
||||
}
|
||||
|
||||
void Client::SetReplayerTimeFactor(double time_factor) {
|
||||
_pimpl->AsyncCall("set_replayer_time_factor", time_factor);
|
||||
}
|
||||
|
||||
void Client::SubscribeToStream(
|
||||
const streaming::Token &token,
|
||||
std::function<void(Buffer)> callback) {
|
||||
|
|
|
@ -174,7 +174,7 @@ namespace detail {
|
|||
|
||||
void StopRecorder();
|
||||
|
||||
std::string ShowRecorderFileInfo(std::string name);
|
||||
std::string ShowRecorderFileInfo(std::string name, bool show_all);
|
||||
|
||||
std::string ShowRecorderCollisions(std::string name, char type1, char type2);
|
||||
|
||||
|
@ -182,6 +182,8 @@ namespace detail {
|
|||
|
||||
std::string ReplayFile(std::string name, double start, double duration, uint32_t follow_id);
|
||||
|
||||
void SetReplayerTimeFactor(double time_factor);
|
||||
|
||||
void SubscribeToStream(
|
||||
const streaming::Token &token,
|
||||
std::function<void(Buffer)> callback);
|
||||
|
|
|
@ -277,8 +277,8 @@ namespace detail {
|
|||
_client.StopRecorder();
|
||||
}
|
||||
|
||||
std::string ShowRecorderFileInfo(std::string name) {
|
||||
return _client.ShowRecorderFileInfo(std::move(name));
|
||||
std::string ShowRecorderFileInfo(std::string name, bool show_all) {
|
||||
return _client.ShowRecorderFileInfo(std::move(name), show_all);
|
||||
}
|
||||
|
||||
std::string ShowRecorderCollisions(std::string name, char type1, char type2) {
|
||||
|
@ -293,6 +293,10 @@ namespace detail {
|
|||
return _client.ReplayFile(std::move(name), start, duration, follow_id);
|
||||
}
|
||||
|
||||
void SetReplayerTimeFactor(double time_factor) {
|
||||
_client.SetReplayerTimeFactor(time_factor);
|
||||
}
|
||||
|
||||
/// @}
|
||||
// =========================================================================
|
||||
/// @name Operations with sensors
|
||||
|
|
|
@ -64,10 +64,11 @@ void export_client() {
|
|||
.def("load_world", CONST_CALL_WITHOUT_GIL_1(cc::Client, LoadWorld, std::string), (arg("map_name")))
|
||||
.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_file_info", CALL_WITHOUT_GIL_2(cc::Client, ShowRecorderFileInfo, std::string, bool), (arg("name"), arg("show_all")))
|
||||
.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")))
|
||||
.def("set_replayer_time_factor", &cc::Client::SetReplayerTimeFactor, (arg("time_factor")))
|
||||
.def("apply_batch", &ApplyBatchCommands, (arg("commands"), arg("do_tick")=false))
|
||||
.def("apply_batch_sync", &ApplyBatchCommandsSync, (arg("commands"), arg("do_tick")=false))
|
||||
;
|
||||
|
|
|
@ -43,6 +43,10 @@ def main():
|
|||
metavar='F',
|
||||
default="test1.rec",
|
||||
help='recorder filename (test1.rec)')
|
||||
argparser.add_argument(
|
||||
'-a', '--show_all',
|
||||
action='store_true',
|
||||
help='show detailed info about all frames content')
|
||||
args = argparser.parse_args()
|
||||
|
||||
try:
|
||||
|
@ -50,7 +54,7 @@ def main():
|
|||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(60.0)
|
||||
|
||||
print(client.show_recorder_file_info(args.recorder_filename))
|
||||
print(client.show_recorder_file_info(args.recorder_filename, args.show_all))
|
||||
|
||||
finally:
|
||||
pass
|
||||
|
|
|
@ -23,6 +23,7 @@ import carla
|
|||
import argparse
|
||||
import random
|
||||
import time
|
||||
import logging
|
||||
|
||||
|
||||
def main():
|
||||
|
@ -69,6 +70,7 @@ def main():
|
|||
args = argparser.parse_args()
|
||||
|
||||
actor_list = []
|
||||
logging.basicConfig(format='%(levelname)s: %(message)s', level=logging.INFO)
|
||||
|
||||
try:
|
||||
|
||||
|
@ -77,24 +79,6 @@ def main():
|
|||
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)
|
||||
|
@ -103,32 +87,58 @@ def main():
|
|||
|
||||
count = args.number_of_vehicles
|
||||
|
||||
print("Recording on file:", client.start_recorder(args.recorder_filename))
|
||||
print("Recording on file: %s" % 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:
|
||||
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')]
|
||||
blueprints = [x for x in blueprints if not x.id.endswith('carlacola')]
|
||||
|
||||
spawn_points = world.get_map().get_spawn_points()
|
||||
number_of_spawn_points = len(spawn_points)
|
||||
|
||||
if count < number_of_spawn_points:
|
||||
random.shuffle(spawn_points)
|
||||
elif count > number_of_spawn_points:
|
||||
msg = 'requested %d vehicles, but could only find %d spawn points'
|
||||
logging.warning(msg, count, number_of_spawn_points)
|
||||
count = number_of_spawn_points
|
||||
|
||||
# @todo cannot import these directly.
|
||||
SpawnActor = carla.command.SpawnActor
|
||||
SetAutopilot = carla.command.SetAutopilot
|
||||
FutureActor = carla.command.FutureActor
|
||||
|
||||
batch = []
|
||||
for n, transform in enumerate(spawn_points):
|
||||
if n >= count:
|
||||
break
|
||||
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')
|
||||
batch.append(SpawnActor(blueprint, transform).then(SetAutopilot(FutureActor, True)))
|
||||
|
||||
while count > 0:
|
||||
time.sleep(args.delay)
|
||||
if try_spawn_random_vehicle_at(random.choice(spawn_points)):
|
||||
count -= 1
|
||||
for response in client.apply_batch_sync(batch):
|
||||
if response.error:
|
||||
logging.error(response.error)
|
||||
else:
|
||||
actor_list.append(response.actor_id)
|
||||
|
||||
print('spawned %d vehicles, press Ctrl+C to exit.' % args.number_of_vehicles)
|
||||
print('spawned %d vehicles, press Ctrl+C to exit.' % len(actor_list))
|
||||
|
||||
if (args.recorder_time > 0):
|
||||
time.sleep(args.recorder_time)
|
||||
else:
|
||||
while True:
|
||||
time.sleep(0.1)
|
||||
world.wait_for_tick()
|
||||
# time.sleep(0.1)
|
||||
|
||||
finally:
|
||||
|
||||
print('\ndestroying %d actors' % len(actor_list))
|
||||
for actor in actor_list:
|
||||
actor.destroy()
|
||||
client.apply_batch([carla.command.DestroyActor(x) for x in actor_list])
|
||||
|
||||
print("Stop recording")
|
||||
client.stop_recorder()
|
||||
|
|
|
@ -61,6 +61,12 @@ def main():
|
|||
default=0,
|
||||
type=int,
|
||||
help='camera follows an actor (ex: 82)')
|
||||
argparser.add_argument(
|
||||
'-x', '--time_factor',
|
||||
metavar='X',
|
||||
default=1.0,
|
||||
type=float,
|
||||
help='time factor (default 1.0)')
|
||||
args = argparser.parse_args()
|
||||
|
||||
try:
|
||||
|
@ -68,6 +74,7 @@ def main():
|
|||
client = carla.Client(args.host, args.port)
|
||||
client.set_timeout(60.0)
|
||||
|
||||
client.set_replayer_time_factor(args.time_factor)
|
||||
print(client.replay_file(args.recorder_filename, args.start, args.duration, args.camera))
|
||||
|
||||
finally:
|
||||
|
|
|
@ -200,6 +200,9 @@ void UCarlaEpisode::InitializeAtBeginPlay()
|
|||
ActorDispatcher->RegisterActor(*Actor, Description);
|
||||
}
|
||||
}
|
||||
|
||||
// check if replayer is waiting to autostart
|
||||
Recorder->GetReplayer()->CheckPlayAfterMapLoaded();
|
||||
}
|
||||
|
||||
void UCarlaEpisode::EndPlay(void)
|
||||
|
@ -218,11 +221,10 @@ void UCarlaEpisode::EndPlay(void)
|
|||
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);
|
||||
result = Recorder->Start(Name, MapName);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
|
|
@ -6,6 +6,7 @@
|
|||
|
||||
// #include "Carla.h"
|
||||
#include "CarlaRecorder.h"
|
||||
#include "CarlaReplayerHelper.h"
|
||||
#include "Carla/Actor/ActorDescription.h"
|
||||
|
||||
#include <ctime>
|
||||
|
@ -24,25 +25,30 @@ ACarlaRecorder::ACarlaRecorder(const FObjectInitializer &ObjectInitializer)
|
|||
Disable();
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ShowFileInfo(std::string Path, std::string Name)
|
||||
std::string ACarlaRecorder::ShowFileInfo(std::string Name, bool bShowAll)
|
||||
{
|
||||
return Query.QueryInfo(Path + Name);
|
||||
return Query.QueryInfo(Name, bShowAll);
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ShowFileCollisions(std::string Path, std::string Name, char Type1, char Type2)
|
||||
std::string ACarlaRecorder::ShowFileCollisions(std::string Name, char Type1, char Type2)
|
||||
{
|
||||
return Query.QueryCollisions(Path + Name, Type1, Type2);
|
||||
return Query.QueryCollisions(Name, Type1, Type2);
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ShowFileActorsBlocked(std::string Path, std::string Name, double MinTime, double MinDistance)
|
||||
std::string ACarlaRecorder::ShowFileActorsBlocked(std::string Name, double MinTime, double MinDistance)
|
||||
{
|
||||
return Query.QueryBlocked(Path + Name, MinTime, MinDistance);
|
||||
return Query.QueryBlocked(Name, MinTime, MinDistance);
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::ReplayFile(std::string Path, std::string Name, double TimeStart, double Duration, uint32_t FollowId)
|
||||
std::string ACarlaRecorder::ReplayFile(std::string Name, double TimeStart, double Duration, uint32_t FollowId)
|
||||
{
|
||||
Stop();
|
||||
return Replayer.ReplayFile(Path + Name, TimeStart, Duration, FollowId);
|
||||
return Replayer.ReplayFile(Name, TimeStart, Duration, FollowId);
|
||||
}
|
||||
|
||||
inline void ACarlaRecorder::SetReplayerTimeFactor(double TimeFactor)
|
||||
{
|
||||
Replayer.SetTimeFactor(TimeFactor);
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Tick(float DeltaSeconds)
|
||||
|
@ -120,7 +126,7 @@ void ACarlaRecorder::Disable(void)
|
|||
Enabled = false;
|
||||
}
|
||||
|
||||
std::string ACarlaRecorder::Start(FString Path, FString Name, FString MapName)
|
||||
std::string ACarlaRecorder::Start(std::string Name, FString MapName)
|
||||
{
|
||||
// stop replayer if any in course
|
||||
if (Replayer.IsEnabled())
|
||||
|
@ -129,13 +135,16 @@ std::string ACarlaRecorder::Start(FString Path, FString Name, FString MapName)
|
|||
// stop recording
|
||||
Stop();
|
||||
|
||||
// reset collisions Id
|
||||
NextCollisionId = 0;
|
||||
FString Filename = Path + Name;
|
||||
|
||||
// get the final path + filename
|
||||
std::string Filename = GetRecorderFilename(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);
|
||||
File.open(Filename, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
return "";
|
||||
|
@ -157,7 +166,7 @@ std::string ACarlaRecorder::Start(FString Path, FString Name, FString MapName)
|
|||
// add all existing actors
|
||||
AddExistingActors();
|
||||
|
||||
return std::string(TCHAR_TO_UTF8(*Filename));
|
||||
return std::string(Filename);
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Stop(void)
|
||||
|
|
|
@ -58,7 +58,7 @@ public:
|
|||
void Disable(void);
|
||||
|
||||
// start / stop
|
||||
std::string Start(FString Path, FString Name, FString MapName);
|
||||
std::string Start(std::string Name, FString MapName);
|
||||
|
||||
void Stop(void);
|
||||
|
||||
|
@ -98,11 +98,12 @@ public:
|
|||
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);
|
||||
// queries
|
||||
std::string ShowFileInfo(std::string Name, bool bShowAll = false);
|
||||
std::string ShowFileCollisions(std::string Name, char Type1, char Type2);
|
||||
std::string ShowFileActorsBlocked(std::string Name, double MinTime = 30, double MinDistance = 10);
|
||||
std::string ReplayFile(std::string Name, double TimeStart, double Duration, uint32_t FollowId);
|
||||
void SetReplayerTimeFactor(double TimeFactor);
|
||||
|
||||
void Tick(float DeltaSeconds) final;
|
||||
|
||||
|
|
|
@ -12,6 +12,23 @@
|
|||
// create a temporal buffer to convert from and to FString and bytes
|
||||
static std::vector<uint8_t> CarlaRecorderHelperBuffer;
|
||||
|
||||
// get the final path + filename
|
||||
std::string GetRecorderFilename(std::string Filename)
|
||||
{
|
||||
std::string Filename2;
|
||||
|
||||
// check if a relative path was specified
|
||||
if (Filename.find("\\") != std::string::npos || Filename.find("/") != std::string::npos || Filename.find(":") != std::string::npos)
|
||||
Filename2 = Filename;
|
||||
else
|
||||
{
|
||||
FString Path = FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir());
|
||||
Filename2 = TCHAR_TO_UTF8(*Path) + Filename;
|
||||
}
|
||||
|
||||
return Filename2;
|
||||
}
|
||||
|
||||
// ------
|
||||
// write
|
||||
// ------
|
||||
|
|
|
@ -8,6 +8,9 @@
|
|||
|
||||
#include <fstream>
|
||||
|
||||
// get the final path + filename
|
||||
std::string GetRecorderFilename(std::string Filename);
|
||||
|
||||
// ---------
|
||||
// recorder
|
||||
// ---------
|
||||
|
|
|
@ -54,11 +54,14 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
|
|||
{
|
||||
std::stringstream Info;
|
||||
|
||||
// get the final path + filename
|
||||
std::string Filename2 = GetRecorderFilename(Filename);
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
File.open(Filename2, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
Info << "File " << Filename2 << " not found on server\n";
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
|
@ -91,6 +94,12 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
|
|||
// frame
|
||||
case static_cast<char>(CarlaRecorderPacketId::FrameStart):
|
||||
Frame.Read(File);
|
||||
if (bShowAll)
|
||||
{
|
||||
PrintFrame(Info);
|
||||
bFramePrinted = true;
|
||||
}
|
||||
else
|
||||
bFramePrinted = false;
|
||||
break;
|
||||
|
||||
|
@ -170,7 +179,22 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
|
|||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::Position):
|
||||
// Info << "Positions\n";
|
||||
if (bShowAll)
|
||||
{
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && !bFramePrinted)
|
||||
{
|
||||
PrintFrame(Info);
|
||||
bFramePrinted = true;
|
||||
}
|
||||
Info << " Positions: " << Total << std::endl;
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
Position.Read(File);
|
||||
Info << " Id: " << Position.DatabaseId << " Location (" << Position.Location.X << ", " << Position.Location.Y << ", " << Position.Location.Z << ") Rotation (" << Position.Rotation.X << ", " << Position.Rotation.Y << ", " << Position.Rotation.Z << ")" << std::endl;
|
||||
}
|
||||
}
|
||||
else
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
|
@ -220,11 +244,14 @@ std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Categ
|
|||
{
|
||||
std::stringstream Info;
|
||||
|
||||
// get the final path + filename
|
||||
std::string Filename2 = GetRecorderFilename(Filename);
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
File.open(Filename2, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
Info << "File " << Filename2 << " not found on server\n";
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
|
@ -393,11 +420,14 @@ std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTim
|
|||
{
|
||||
std::stringstream Info;
|
||||
|
||||
// get the final path + filename
|
||||
std::string Filename2 = GetRecorderFilename(Filename);
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
File.open(Filename2, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
Info << "File " << Filename2 << " not found on server\n";
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
|
|
|
@ -10,6 +10,9 @@
|
|||
#include <ctime>
|
||||
#include <sstream>
|
||||
|
||||
// structure to save replaying info when need to load a new map (static member by now)
|
||||
CarlaReplayer::PlayAfterLoadMap CarlaReplayer::Autoplay { false, "", "", 0.0, 0.0, 0, 1.0 };
|
||||
|
||||
void CarlaReplayer::Stop(bool bKeepActors)
|
||||
{
|
||||
if (Enabled)
|
||||
|
@ -22,20 +25,11 @@ void CarlaReplayer::Stop(bool 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)"));
|
||||
}
|
||||
File.close();
|
||||
}
|
||||
|
||||
bool CarlaReplayer::ReadHeader()
|
||||
|
@ -73,8 +67,6 @@ void CarlaReplayer::Rewind(void)
|
|||
|
||||
// read geneal Info
|
||||
RecInfo.Read(File);
|
||||
|
||||
// UE_LOG(LogCarla, Log, TEXT("Replayer rewind"));
|
||||
}
|
||||
|
||||
// read last frame in File and return the Total time recorded
|
||||
|
@ -119,56 +111,136 @@ std::string CarlaReplayer::ReplayFile(std::string Filename, double TimeStart, do
|
|||
Stop();
|
||||
}
|
||||
|
||||
Info << "Replaying File: " << Filename << std::endl;
|
||||
// get the final path + filename
|
||||
std::string Filename2 = GetRecorderFilename(Filename);
|
||||
|
||||
Info << "Replaying File: " << Filename2 << std::endl;
|
||||
|
||||
// try to open
|
||||
File.open(Filename, std::ios::binary);
|
||||
File.open(Filename2, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
Info << "File " << Filename << " not found on server\n";
|
||||
Info << "File " << Filename2 << " not found on server\n";
|
||||
Stop();
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
// from start
|
||||
Rewind();
|
||||
|
||||
// check to load map if different
|
||||
if (Episode->GetMapName() != RecInfo.Mapfile)
|
||||
{
|
||||
if (!Episode->LoadNewEpisode(RecInfo.Mapfile))
|
||||
{
|
||||
Info << "Could not load mapfile " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl;
|
||||
Stop();
|
||||
return Info.str();
|
||||
}
|
||||
Info << "Loading map " << TCHAR_TO_UTF8(*RecInfo.Mapfile) << std::endl;
|
||||
Info << "Replayer will start after map is loaded..." << std::endl;
|
||||
|
||||
// prepare autoplay after map is loaded
|
||||
Autoplay.Enabled = true;
|
||||
Autoplay.Filename = Filename2;
|
||||
Autoplay.Mapfile = RecInfo.Mapfile;
|
||||
Autoplay.TimeStart = TimeStart;
|
||||
Autoplay.Duration = Duration;
|
||||
Autoplay.FollowId = FollowId;
|
||||
Autoplay.TimeFactor = TimeFactor;
|
||||
}
|
||||
|
||||
// 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) at " <<
|
||||
std::setprecision(1) << std::fixed << TimeFactor << "x" << std::endl;
|
||||
|
||||
// set the follow Id
|
||||
FollowId = ThisFollowId;
|
||||
|
||||
// if we don't need to load a new map, then start
|
||||
if (!Autoplay.Enabled)
|
||||
{
|
||||
// process all events until the time
|
||||
ProcessToTime(TimeStart);
|
||||
// mark as enabled
|
||||
Enabled = true;
|
||||
}
|
||||
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
void CarlaReplayer::CheckPlayAfterMapLoaded(void)
|
||||
{
|
||||
|
||||
// check if the autoplay is enabled (means waiting until map is loaded)
|
||||
if (!Autoplay.Enabled)
|
||||
return;
|
||||
|
||||
// disable
|
||||
Autoplay.Enabled = false;
|
||||
|
||||
// check to stop if we are replaying another
|
||||
if (Enabled)
|
||||
{
|
||||
Stop();
|
||||
}
|
||||
|
||||
// try to open
|
||||
File.open(Autoplay.Filename, std::ios::binary);
|
||||
if (!File.is_open())
|
||||
{
|
||||
return;
|
||||
}
|
||||
|
||||
// from start
|
||||
Rewind();
|
||||
|
||||
// get Total time of recorder
|
||||
TotalTime = GetTotalTime();
|
||||
Info << "Total time recorded: " << TotalTime << std::endl;
|
||||
|
||||
// set time to start replayer
|
||||
double TimeStart = Autoplay.TimeStart;
|
||||
if (TimeStart < 0.0f)
|
||||
{
|
||||
TimeStart = TotalTime + TimeStart;
|
||||
TimeStart = TotalTime + Autoplay.TimeStart;
|
||||
if (TimeStart < 0.0f)
|
||||
{
|
||||
TimeStart = 0.0f;
|
||||
}
|
||||
}
|
||||
|
||||
// set time to stop replayer
|
||||
if (Duration > 0.0f)
|
||||
{
|
||||
TimeToStop = TimeStart + Duration;
|
||||
}
|
||||
if (Autoplay.Duration > 0.0f)
|
||||
TimeToStop = TimeStart + Autoplay.Duration;
|
||||
else
|
||||
{
|
||||
TimeToStop = TotalTime;
|
||||
}
|
||||
Info << "Replaying from " << TimeStart << " s - " << TimeToStop << " s (" << TotalTime << " s)" <<
|
||||
std::endl;
|
||||
|
||||
// set the follow Id
|
||||
FollowId = Autoplay.FollowId;
|
||||
|
||||
// apply time factor
|
||||
TimeFactor = Autoplay.TimeFactor;
|
||||
|
||||
// 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)
|
||||
|
@ -302,18 +374,15 @@ void CarlaReplayer::ProcessEventsAdd(void)
|
|||
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());
|
||||
*/
|
||||
// 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, TEXT("%s"), Info.str().c_str());
|
||||
|
||||
// auto Result = CallbackEventAdd(
|
||||
auto Result = Helper.ProcessReplayerEventAdd(
|
||||
|
@ -331,10 +400,14 @@ void CarlaReplayer::ProcessEventsAdd(void)
|
|||
|
||||
// actor created but with different id
|
||||
case 1:
|
||||
if (Result.second != EventAdd.DatabaseId)
|
||||
{
|
||||
// if (Result.second != EventAdd.DatabaseId)
|
||||
// {
|
||||
// UE_LOG(LogCarla, Log, TEXT("actor created but with different id"));
|
||||
}
|
||||
// }
|
||||
// else
|
||||
// {
|
||||
// UE_LOG(LogCarla, Log, TEXT("actor created with same id"));
|
||||
// }
|
||||
// mapping id (recorded Id is a new Id in replayer)
|
||||
MappedId[EventAdd.DatabaseId] = Result.second;
|
||||
break;
|
||||
|
@ -433,6 +506,8 @@ void CarlaReplayer::ProcessPositions(void)
|
|||
{
|
||||
Pos.DatabaseId = NewId->second;
|
||||
}
|
||||
else
|
||||
UE_LOG(LogCarla, Log, TEXT("Actor not found when trying to move from replayer (id. %d)"), Pos.DatabaseId);
|
||||
CurrPos.push_back(std::move(Pos));
|
||||
}
|
||||
}
|
||||
|
@ -467,13 +542,18 @@ void CarlaReplayer::UpdatePositions(double Per)
|
|||
auto Result = TempMap.find(CurrPos[i].DatabaseId);
|
||||
if (Result != TempMap.end())
|
||||
{
|
||||
// check if time factor is high
|
||||
if (TimeFactor >= 2.0)
|
||||
// assign first position
|
||||
InterpolatePosition(PrevPos[Result->second], CurrPos[i], 0.0);
|
||||
else
|
||||
// interpolate
|
||||
InterpolatePosition(PrevPos[Result->second], CurrPos[i], Per);
|
||||
}
|
||||
else
|
||||
{
|
||||
// assign last position (we don't have previous one)
|
||||
InterpolatePosition(CurrPos[i], CurrPos[i], 0);
|
||||
InterpolatePosition(CurrPos[i], CurrPos[i], 0.0);
|
||||
}
|
||||
|
||||
// move the camera to follow this actor if required
|
||||
|
@ -502,7 +582,7 @@ void CarlaReplayer::Tick(float Delta)
|
|||
// check if there are events to process
|
||||
if (Enabled)
|
||||
{
|
||||
ProcessToTime(Delta);
|
||||
ProcessToTime(Delta * TimeFactor);
|
||||
}
|
||||
|
||||
// UE_LOG(LogCarla, Log, TEXT("Replayer tick"));
|
||||
|
|
|
@ -35,6 +35,18 @@ class CarlaReplayer
|
|||
#pragma pack(pop)
|
||||
|
||||
public:
|
||||
struct PlayAfterLoadMap
|
||||
{
|
||||
bool Enabled;
|
||||
std::string Filename;
|
||||
FString Mapfile;
|
||||
double TimeStart;
|
||||
double Duration;
|
||||
uint32_t FollowId;
|
||||
double TimeFactor;
|
||||
};
|
||||
|
||||
static PlayAfterLoadMap Autoplay;
|
||||
|
||||
CarlaReplayer() {};
|
||||
~CarlaReplayer() { Stop(); };
|
||||
|
@ -60,6 +72,15 @@ public:
|
|||
Helper.SetEpisode(ThisEpisode);
|
||||
}
|
||||
|
||||
// playback speed (time factor)
|
||||
void SetTimeFactor(double NewTimeFactor)
|
||||
{
|
||||
TimeFactor = NewTimeFactor;
|
||||
}
|
||||
|
||||
// check if after a map is loaded, we need to replay
|
||||
void CheckPlayAfterMapLoaded(void);
|
||||
|
||||
// tick for the replayer
|
||||
void Tick(float Time);
|
||||
|
||||
|
@ -85,6 +106,8 @@ private:
|
|||
CarlaReplayerHelper Helper;
|
||||
// follow camera
|
||||
uint32_t FollowId;
|
||||
// speed (time factor)
|
||||
double TimeFactor { 1.0 };
|
||||
|
||||
// utils
|
||||
bool ReadHeader();
|
||||
|
|
|
@ -9,7 +9,7 @@
|
|||
#include "Carla/Actor/ActorDescription.h"
|
||||
|
||||
// create or reuse an actor for replaying
|
||||
std::pair<int, FActorView &>CarlaReplayerHelper::TryToCreateReplayerActor(
|
||||
std::pair<int, FActorView>CarlaReplayerHelper::TryToCreateReplayerActor(
|
||||
FVector &Location,
|
||||
FVector &Rotation,
|
||||
FActorDescription &ActorDesc,
|
||||
|
@ -29,13 +29,13 @@ std::pair<int, FActorView &>CarlaReplayerHelper::TryToCreateReplayerActor(
|
|||
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);
|
||||
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);
|
||||
return std::pair<int, FActorView>(0, view_empty);
|
||||
}
|
||||
}
|
||||
else if (!ActorDesc.Id.StartsWith("sensor."))
|
||||
|
@ -50,7 +50,7 @@ std::pair<int, FActorView &>CarlaReplayerHelper::TryToCreateReplayerActor(
|
|||
if (desc->Id == ActorDesc.Id)
|
||||
{
|
||||
// we don't need to create, actor of same type already exist
|
||||
return std::pair<int, FActorView &>(2, view);
|
||||
return std::pair<int, FActorView>(2, view);
|
||||
}
|
||||
}
|
||||
// create the transform
|
||||
|
@ -66,18 +66,18 @@ std::pair<int, FActorView &>CarlaReplayerHelper::TryToCreateReplayerActor(
|
|||
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);
|
||||
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);
|
||||
return std::pair<int, FActorView>(0, Result.Value);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
// actor ignored
|
||||
return std::pair<int, FActorView &>(0, view_empty);
|
||||
return std::pair<int, FActorView>(0, view_empty);
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -228,11 +228,21 @@ bool CarlaReplayerHelper::ProcessReplayerPosition(CarlaRecorderPosition Pos1, Ca
|
|||
AActor *Actor = Episode->GetActorRegistry().Find(Pos1.DatabaseId).GetActor();
|
||||
if (Actor && !Actor->IsPendingKill())
|
||||
{
|
||||
// interpolate transform
|
||||
// check to assign first position or interpolate between both
|
||||
if (Per == 0.0)
|
||||
{
|
||||
// assign position 1
|
||||
FTransform Trans(FRotator::MakeFromEuler(Pos1.Rotation), FVector(Pos1.Location), FVector(1, 1, 1));
|
||||
Actor->SetActorTransform(Trans, false, nullptr, ETeleportType::TeleportPhysics);
|
||||
}
|
||||
else
|
||||
{
|
||||
// interpolate positions
|
||||
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;
|
||||
|
|
|
@ -50,7 +50,7 @@ private:
|
|||
|
||||
UCarlaEpisode *Episode {nullptr};
|
||||
|
||||
std::pair<int, FActorView &>TryToCreateReplayerActor(
|
||||
std::pair<int, FActorView>TryToCreateReplayerActor(
|
||||
FVector &Location,
|
||||
FVector &Rotation,
|
||||
FActorDescription &ActorDesc,
|
||||
|
|
|
@ -722,19 +722,18 @@ void FTheNewCarlaServer::FPimpl::BindActions()
|
|||
return R<void>::Success();
|
||||
};
|
||||
|
||||
BIND_SYNC(show_recorder_file_info) << [this](std::string name) -> R<std::string>
|
||||
BIND_SYNC(show_recorder_file_info) << [this](std::string name, bool show_all) -> R<std::string>
|
||||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder()->ShowFileInfo(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name));
|
||||
name,
|
||||
show_all));
|
||||
};
|
||||
|
||||
BIND_SYNC(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));
|
||||
|
@ -744,7 +743,6 @@ void FTheNewCarlaServer::FPimpl::BindActions()
|
|||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder()->ShowFileActorsBlocked(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name,
|
||||
min_time,
|
||||
min_distance));
|
||||
|
@ -754,13 +752,19 @@ void FTheNewCarlaServer::FPimpl::BindActions()
|
|||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder()->ReplayFile(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name,
|
||||
start,
|
||||
duration,
|
||||
follow_id));
|
||||
};
|
||||
|
||||
BIND_SYNC(set_replayer_time_factor) << [this](double time_factor) -> R<void>
|
||||
{
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
Episode->GetRecorder()->SetReplayerTimeFactor(time_factor);
|
||||
return R<void>::Success();
|
||||
};
|
||||
|
||||
// ~~ Draw debug shapes ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
|
||||
|
||||
BIND_SYNC(draw_debug_shape) << [this](const cr::DebugShape &shape) -> R<void>
|
||||
|
|
Loading…
Reference in New Issue