Removed some commented code

This commit is contained in:
bernatx 2019-05-21 18:48:22 +02:00
parent 58f00c9a3d
commit faa164557f
6 changed files with 13 additions and 55 deletions

View File

@ -1,7 +1,7 @@
## Latest
* Upgraded to Unreal Engine 4.22
* Recorder fixes:
- Fixed a possible crash if an actor is respawned before the episode is ready when a new map is loaded automatically.
- Actors at start of playback could interpolate positions from its current position instead than the recorded position, making some fast sliding effect during 1 frame.
- Camera following in playback was not working if a new map was needed to load.
- API function 'show_recorder_file_info' was showing the wrong parent id.

View File

@ -111,7 +111,10 @@ void ACarlaGameModeBase::BeginPlay()
/// @todo Recorder should not tick here, FCarlaEngine should do it.
// check if replayer is waiting to autostart
if (Recorder) Recorder->GetReplayer()->CheckPlayAfterMapLoaded();
if (Recorder)
{
Recorder->GetReplayer()->CheckPlayAfterMapLoaded();
}
}
void ACarlaGameModeBase::Tick(float DeltaSeconds)
@ -119,7 +122,10 @@ void ACarlaGameModeBase::Tick(float DeltaSeconds)
Super::Tick(DeltaSeconds);
/// @todo Recorder should not tick here, FCarlaEngine should do it.
if (Recorder) Recorder->Tick(DeltaSeconds);
if (Recorder)
{
Recorder->Tick(DeltaSeconds);
}
}
void ACarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)

View File

@ -215,8 +215,6 @@ std::string ACarlaRecorder::Start(std::string Name, FString MapName)
std::string Filename = GetRecorderFilename(Name);
// binary file
// file.open(filename.str(), std::ios::binary | std::ios::trunc |
// std::ios::out);
File.open(Filename, std::ios::binary);
if (!File.is_open())
{

View File

@ -72,7 +72,6 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
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))
@ -178,6 +177,7 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
}
break;
// positions
case static_cast<char>(CarlaRecorderPacketId::Position):
if (bShowAll)
{
@ -198,6 +198,7 @@ std::string CarlaRecorderQuery::QueryInfo(std::string Filename, bool bShowAll)
SkipPacket();
break;
// traffic light
case static_cast<char>(CarlaRecorderPacketId::State):
if (bShowAll)
{
@ -412,14 +413,12 @@ std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Categ
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
@ -429,7 +428,6 @@ std::string CarlaRecorderQuery::QueryCollisions(std::string Filename, char Categ
break;
case static_cast<char>(CarlaRecorderPacketId::Position):
// Info << "Positions\n";
SkipPacket();
break;
@ -546,6 +544,7 @@ std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTim
SkipPacket();
break;
// positions
case static_cast<char>(CarlaRecorderPacketId::Position):
// read all positions
ReadValue<uint16_t>(File, Total);
@ -580,6 +579,7 @@ std::string CarlaRecorderQuery::QueryBlocked(std::string Filename, double MinTim
}
break;
// traffic light
case static_cast<char>(CarlaRecorderPacketId::State):
SkipPacket();
break;

View File

@ -257,7 +257,6 @@ void CarlaReplayer::ProcessToTime(double Time, bool IsFirstTime)
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
@ -278,7 +277,6 @@ void CarlaReplayer::ProcessToTime(double Time, bool IsFirstTime)
{
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;
@ -378,7 +376,6 @@ void CarlaReplayer::ProcessEventsAdd(void)
{
uint16_t i, Total;
CarlaRecorderEventAdd EventAdd;
// std::stringstream Info;
// process creation events
ReadValue<uint16_t>(File, Total);
@ -386,17 +383,6 @@ void CarlaReplayer::ProcessEventsAdd(void)
{
EventAdd.Read(File);
// 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, TEXT("%s"), Info.str().c_str());
// auto Result = CallbackEventAdd(
auto Result = Helper.ProcessReplayerEventAdd(
EventAdd.Location,
@ -413,21 +399,12 @@ void CarlaReplayer::ProcessEventsAdd(void)
// actor created but with different id
case 1:
// 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;
// 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;
@ -439,16 +416,12 @@ 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);
}
@ -465,10 +438,6 @@ void CarlaReplayer::ProcessEventsParent(void)
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]);
}
}
@ -485,7 +454,6 @@ void CarlaReplayer::ProcessStates(void)
{
StateTrafficLight.Read(File);
// UE_LOG(LogCarla, Log, TEXT("calling callback add"));
StateTrafficLight.DatabaseId = MappedId[StateTrafficLight.DatabaseId];
if (!Helper.ProcessReplayerStateTrafficLight(StateTrafficLight))
{
@ -581,7 +549,6 @@ void CarlaReplayer::UpdatePositions(double Per, double DeltaTime)
if (NewId != MappedId.end())
{
NewFollowId = NewId->second;
// UE_LOG(LogCarla, Log, TEXT("Following %d (%d)"), NewFollowId, FollowId);
}
}
@ -611,7 +578,6 @@ void CarlaReplayer::UpdatePositions(double Per, double DeltaTime)
{
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}));
}
}
}
@ -635,6 +601,4 @@ void CarlaReplayer::Tick(float Delta)
{
ProcessToTime(Delta * TimeFactor, false);
}
// UE_LOG(LogCarla, Log, TEXT("Replayer tick"));
}

View File

@ -33,7 +33,6 @@ std::pair<int, FActorView>CarlaReplayerHelper::TryToCreateReplayerActor(
// 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
@ -46,12 +45,10 @@ std::pair<int, FActorView>CarlaReplayerHelper::TryToCreateReplayerActor(
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
@ -60,17 +57,14 @@ std::pair<int, FActorView>CarlaReplayerHelper::TryToCreateReplayerActor(
}
// 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
@ -96,7 +90,6 @@ AActor *CarlaReplayerHelper::FindTrafficLightAt(FVector Location)
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)
@ -107,7 +100,6 @@ AActor *CarlaReplayerHelper::FindTrafficLightAt(FVector Location)
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
@ -220,7 +212,6 @@ bool CarlaReplayerHelper::ProcessReplayerEventParent(uint32_t ChildId, uint32_t
{
child->AttachToActor(parent, FAttachmentTransformRules::KeepRelativeTransform);
child->SetOwner(parent);
// UE_LOG(LogCarla, Log, TEXT("Parenting Actor"));
return true;
}
else
@ -280,7 +271,6 @@ bool CarlaReplayerHelper::SetCameraPosition(uint32_t Id, FVector Offset, FQuat R
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;
}