Moved Recorder code from LibCarla to Unreal
This commit is contained in:
parent
483b1c1f66
commit
12dd144400
|
@ -20,9 +20,6 @@ install(FILES ${libcarla_carla_headers} DESTINATION include/carla)
|
|||
file(GLOB libcarla_carla_geom_headers "${libcarla_source_path}/carla/geom/*.h")
|
||||
install(FILES ${libcarla_carla_geom_headers} DESTINATION include/carla/geom)
|
||||
|
||||
file(GLOB libcarla_carla_recorder_headers "${libcarla_source_path}/carla/recorder/*.h")
|
||||
install(FILES ${libcarla_carla_recorder_headers} DESTINATION include/carla/recorder)
|
||||
|
||||
file(GLOB libcarla_carla_profiler_headers "${libcarla_source_path}/carla/profiler/*.h")
|
||||
install(FILES ${libcarla_carla_profiler_headers} DESTINATION include/carla/profiler)
|
||||
|
||||
|
@ -92,8 +89,6 @@ file(GLOB libcarla_server_sources
|
|||
"${libcarla_source_path}/carla/opendrive/parser/*.h"
|
||||
"${libcarla_source_path}/carla/opendrive/parser/pugixml/*.cpp"
|
||||
"${libcarla_source_path}/carla/opendrive/parser/pugixml/*.hpp"
|
||||
"${libcarla_source_path}/carla/recorder/*.cpp"
|
||||
"${libcarla_source_path}/carla/recorder/*.h"
|
||||
"${libcarla_source_path}/carla/road/*.cpp"
|
||||
"${libcarla_source_path}/carla/road/*.h"
|
||||
"${libcarla_source_path}/carla/road/element/*.cpp"
|
||||
|
|
|
@ -1,107 +0,0 @@
|
|||
// 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 "Recorder.h"
|
||||
|
||||
#include <ctime>
|
||||
#include <sstream>
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
|
||||
Recorder::Recorder(){
|
||||
}
|
||||
|
||||
Recorder::~Recorder(){
|
||||
}
|
||||
|
||||
std::string Recorder::start(std::string path, std::string name, std::string mapName) {
|
||||
|
||||
// reset
|
||||
stop();
|
||||
|
||||
std::stringstream filename;
|
||||
filename << path << name;
|
||||
|
||||
// files
|
||||
// file.open(filename.str(), std::ios::binary | std::ios::trunc | std::ios::out);
|
||||
file.open(filename.str(), std::ios::binary);
|
||||
if (!file.is_open()) {
|
||||
log_error("Recorder file couldn't be created");
|
||||
return "";
|
||||
}
|
||||
|
||||
// log
|
||||
log.open(filename.str() + ".log");
|
||||
|
||||
std::string magic("CARLA_RECORDER");
|
||||
// save info
|
||||
info.version = 1;
|
||||
info.magic.copy_from(magic);
|
||||
info.date = std::time(0);
|
||||
info.mapfile.copy_from(mapName);
|
||||
|
||||
// write general info
|
||||
info.write(file);
|
||||
|
||||
frames.reset();
|
||||
enabled = true;
|
||||
|
||||
return filename.str();
|
||||
}
|
||||
|
||||
void Recorder::stop() {
|
||||
enabled = false;
|
||||
if (file.is_open()) file.close();
|
||||
if (log.is_open()) log.close();
|
||||
// log << "Stop\n";
|
||||
clear();
|
||||
}
|
||||
|
||||
void Recorder::clear(void) {
|
||||
events.clear();
|
||||
positions.clear();
|
||||
states.clear();
|
||||
|
||||
// log << "Clear\n";
|
||||
}
|
||||
|
||||
void Recorder::write(void) {
|
||||
// update this frame data
|
||||
// log << "Write\n";
|
||||
frames.setFrame();
|
||||
frames.write(file, log);
|
||||
events.write(file, log);
|
||||
positions.write(file, log);
|
||||
states.write(file, log);
|
||||
|
||||
clear();
|
||||
}
|
||||
|
||||
void Recorder::addPosition(const RecorderPosition position) {
|
||||
if (enabled)
|
||||
positions.addPosition(std::move(position));
|
||||
}
|
||||
void Recorder::addEvent(RecorderEventAdd event) {
|
||||
if (enabled)
|
||||
events.addEvent(std::move(event));
|
||||
}
|
||||
void Recorder::addEvent(const RecorderEventDel event) {
|
||||
if (enabled)
|
||||
events.addEvent(std::move(event));
|
||||
}
|
||||
void Recorder::addEvent(const RecorderEventParent event) {
|
||||
if (enabled)
|
||||
events.addEvent(std::move(event));
|
||||
}
|
||||
void Recorder::addState(const RecorderStateTrafficLight state) {
|
||||
if (enabled)
|
||||
states.addState(std::move(state));
|
||||
}
|
||||
|
||||
}
|
||||
}
|
|
@ -1,80 +0,0 @@
|
|||
// 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 "carla/NonCopyable.h"
|
||||
#include "carla/recorder/RecorderInfo.h"
|
||||
#include "carla/recorder/RecorderFrames.h"
|
||||
#include "carla/recorder/RecorderEvent.h"
|
||||
#include "carla/recorder/RecorderPosition.h"
|
||||
#include "carla/recorder/RecorderState.h"
|
||||
#include "carla/recorder/RecorderHelpers.h"
|
||||
#include "carla/recorder/Replayer.h"
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
enum class RecorderPacketId : char {
|
||||
Frame = 0,
|
||||
Event,
|
||||
Position,
|
||||
State
|
||||
};
|
||||
|
||||
class Recorder : private NonCopyable {
|
||||
|
||||
bool enabled; // enabled or not
|
||||
|
||||
// files
|
||||
std::ofstream file;
|
||||
std::ofstream log;
|
||||
|
||||
// structures
|
||||
RecorderInfo info;
|
||||
RecorderFrames frames;
|
||||
RecorderEvents events;
|
||||
RecorderPositions positions;
|
||||
RecorderStates states;
|
||||
|
||||
// replayer
|
||||
Replayer replayer;
|
||||
|
||||
public:
|
||||
|
||||
Recorder();
|
||||
~Recorder();
|
||||
void enable(void);
|
||||
void disable(void);
|
||||
bool isEnabled(void) { return enabled; };
|
||||
std::string start(std::string path, std::string name, std::string mapName);
|
||||
void stop(void);
|
||||
void clear(void);
|
||||
void addEvent(RecorderEventAdd event);
|
||||
void addEvent(const RecorderEventDel event);
|
||||
void addEvent(const RecorderEventParent event);
|
||||
void addPosition(const RecorderPosition position);
|
||||
void addState(const RecorderStateTrafficLight state);
|
||||
void write(void);
|
||||
|
||||
|
||||
// replayer
|
||||
Replayer &getReplayer(void) {
|
||||
return replayer;
|
||||
}
|
||||
std::string showFileInfo(std::string path, std::string name) {
|
||||
return replayer.getInfo(path + name);
|
||||
}
|
||||
std::string replayFile(std::string path, std::string name, double timeStart, double duration) {
|
||||
stop();
|
||||
return replayer.replayFile(path + name, timeStart, duration);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
}
|
|
@ -1,171 +0,0 @@
|
|||
// 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 "Recorder.h"
|
||||
#include "RecorderEvent.h"
|
||||
#include "RecorderHelpers.h"
|
||||
|
||||
#include "carla/rpc/ActorId.h"
|
||||
#include "carla/rpc/ActorAttribute.h"
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
void RecorderEventAdd::write(std::ofstream &file) {
|
||||
//log << "add event: " << this->description.id.c_str() << " (id." << this->databaseId << ")\n";
|
||||
// database id
|
||||
writeValue<uint32_t>(file, this->databaseId);
|
||||
// transform
|
||||
writeTransform(file, this->transform);
|
||||
// description type
|
||||
writeValue<carla::rpc::actor_id_type>(file, this->description.uid);
|
||||
writeBuffer(file, this->description.id);
|
||||
// attributes
|
||||
uint16_t total = this->description.attributes.size();
|
||||
writeValue<uint16_t>(file, total);
|
||||
//log << "Attributes: " << this->description.attributes.size() << std::endl;
|
||||
for (uint16_t i=0; i<total; ++i) {
|
||||
// type
|
||||
writeValue<carla::rpc::ActorAttributeType>(file, this->description.attributes[i].type);
|
||||
writeBuffer(file, this->description.attributes[i].id);
|
||||
writeBuffer(file, this->description.attributes[i].value);
|
||||
// log
|
||||
//log << " " << att.id.c_str() << " = " << att.value.c_str() << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
void RecorderEventAdd::read(std::ifstream &file) {
|
||||
//log << "add event: " << this->description.id.c_str() << " (id." << this->databaseId << ")\n";
|
||||
// database id
|
||||
readValue<uint32_t>(file, this->databaseId);
|
||||
// transform
|
||||
readTransform(file, this->transform);
|
||||
// description type
|
||||
readValue<carla::rpc::actor_id_type>(file, this->description.uid);
|
||||
// text id
|
||||
readBuffer(file, this->description.id);
|
||||
// attributes
|
||||
uint16_t total;
|
||||
readValue<uint16_t>(file, total);
|
||||
this->description.attributes.clear();
|
||||
this->description.attributes.reserve(total);
|
||||
//log << "Attributes: " << this->description.attributes.size() << std::endl;
|
||||
for (uint16_t i=0; i<total; ++i) {
|
||||
RecorderActorAttribute att;
|
||||
// type
|
||||
readValue<carla::rpc::ActorAttributeType>(file, att.type);
|
||||
readBuffer(file, att.id);
|
||||
readBuffer(file, att.value);
|
||||
this->description.attributes.push_back(std::move(att));
|
||||
// log
|
||||
//log << " " << att.id.c_str() << " = " << att.value.c_str() << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
void RecorderEventDel::read(std::ifstream &file) {
|
||||
// database id
|
||||
readValue<uint32_t>(file, this->databaseId);
|
||||
}
|
||||
void RecorderEventDel::write(std::ofstream &file) {
|
||||
// database id
|
||||
writeValue<uint32_t>(file, this->databaseId);
|
||||
}
|
||||
|
||||
void RecorderEventParent::read(std::ifstream &file) {
|
||||
// database id
|
||||
readValue<uint32_t>(file, this->databaseId);
|
||||
// database id parent
|
||||
readValue<uint32_t>(file, this->databaseIdParent);
|
||||
}
|
||||
void RecorderEventParent::write(std::ofstream &file) {
|
||||
// database id
|
||||
writeValue<uint32_t>(file, this->databaseId);
|
||||
// database id parent
|
||||
writeValue<uint32_t>(file, this->databaseIdParent);
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
void RecorderEvents::clear(void) {
|
||||
eventsAdd.clear();
|
||||
eventsDel.clear();
|
||||
eventsParent.clear();
|
||||
}
|
||||
|
||||
void RecorderEvents::addEvent(RecorderEventAdd event) {
|
||||
eventsAdd.push_back(std::move(event));
|
||||
}
|
||||
|
||||
void RecorderEvents::addEvent(const RecorderEventDel event) {
|
||||
eventsDel.push_back(std::move(event));
|
||||
}
|
||||
|
||||
void RecorderEvents::addEvent(const RecorderEventParent event) {
|
||||
eventsParent.push_back(std::move(event));
|
||||
}
|
||||
|
||||
void RecorderEvents::writeEventsAdd(std::ofstream &file) {
|
||||
// write total records
|
||||
uint16_t total = eventsAdd.size();
|
||||
writeValue<uint16_t>(file, total);
|
||||
|
||||
for (unsigned long i=0; i<eventsAdd.size(); ++i) {
|
||||
eventsAdd[i].write(file);
|
||||
}
|
||||
}
|
||||
|
||||
void RecorderEvents::writeEventsDel(std::ofstream &file, std::ofstream &log) {
|
||||
|
||||
// write total records
|
||||
uint16_t total = eventsDel.size();
|
||||
writeValue<uint16_t>(file, total);
|
||||
|
||||
for (auto rec : eventsDel) {
|
||||
log << "add del: " << rec.databaseId << "\n";
|
||||
rec.write(file);
|
||||
}
|
||||
}
|
||||
|
||||
void RecorderEvents::writeEventsParent(std::ofstream &file, std::ofstream &log) {
|
||||
|
||||
// write total records
|
||||
uint16_t total = eventsParent.size();
|
||||
writeValue<uint16_t>(file, total);
|
||||
|
||||
for (auto rec : eventsParent) {
|
||||
log << "add parent: id." << rec.databaseId << ", parent." << rec.databaseIdParent << "\n";
|
||||
rec.write(file);
|
||||
}
|
||||
}
|
||||
|
||||
void RecorderEvents::write(std::ofstream &file, std::ofstream &log) {
|
||||
|
||||
// write the packet id
|
||||
writeValue<char>(file, static_cast<char>(RecorderPacketId::Event));
|
||||
|
||||
std::streampos posStart = file.tellp();
|
||||
|
||||
// write a dummy packet size
|
||||
uint32_t total = 0;
|
||||
writeValue<uint32_t>(file, total);
|
||||
|
||||
// write events
|
||||
writeEventsAdd(file);
|
||||
writeEventsDel(file, log);
|
||||
writeEventsParent(file, log);
|
||||
|
||||
// write the real packet size
|
||||
std::streampos posEnd = file.tellp();
|
||||
total = posEnd - posStart - sizeof(uint32_t);
|
||||
file.seekp(posStart, std::ios::beg);
|
||||
writeValue<uint32_t>(file, total);
|
||||
file.seekp(posEnd, std::ios::beg);
|
||||
|
||||
log << "write events (" << eventsAdd.size() << "," << eventsDel.size() << "," << eventsParent.size() << ")\n";
|
||||
}
|
||||
|
||||
}
|
||||
}
|
|
@ -1,74 +0,0 @@
|
|||
// 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 "carla/rpc/ActorDescription.h"
|
||||
#include "carla/rpc/ActorAttributeType.h"
|
||||
#include "carla/geom/Transform.h"
|
||||
#include <fstream>
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
struct RecorderActorAttribute {
|
||||
carla::rpc::ActorAttributeType type = carla::rpc::ActorAttributeType::Int;
|
||||
Buffer id; // string
|
||||
Buffer value; // string
|
||||
};
|
||||
|
||||
struct RecorderActorDescription {
|
||||
carla::rpc::actor_id_type uid = 0u;
|
||||
Buffer id; // string
|
||||
std::vector<RecorderActorAttribute> attributes;
|
||||
};
|
||||
|
||||
struct RecorderEventAdd {
|
||||
uint32_t databaseId;
|
||||
carla::geom::Transform transform;
|
||||
RecorderActorDescription description;
|
||||
|
||||
void read(std::ifstream &file);
|
||||
void write(std::ofstream &file);
|
||||
};
|
||||
|
||||
struct RecorderEventDel {
|
||||
uint32_t databaseId;
|
||||
|
||||
void read(std::ifstream &file);
|
||||
void write(std::ofstream &file);
|
||||
};
|
||||
|
||||
struct RecorderEventParent {
|
||||
uint32_t databaseId;
|
||||
uint32_t databaseIdParent;
|
||||
|
||||
void read(std::ifstream &file);
|
||||
void write(std::ofstream &file);
|
||||
};
|
||||
|
||||
class RecorderEvents {
|
||||
|
||||
public:
|
||||
RecorderEvents() = default;
|
||||
void addEvent(RecorderEventAdd event);
|
||||
void addEvent(const RecorderEventDel event);
|
||||
void addEvent(const RecorderEventParent event);
|
||||
void clear(void);
|
||||
void write(std::ofstream &_file, std::ofstream &log);
|
||||
|
||||
private:
|
||||
std::vector<RecorderEventAdd> eventsAdd;
|
||||
std::vector<RecorderEventDel> eventsDel;
|
||||
std::vector<RecorderEventParent> eventsParent;
|
||||
|
||||
void writeEventsAdd(std::ofstream &file);
|
||||
void writeEventsDel(std::ofstream &file, std::ofstream &log);
|
||||
void writeEventsParent(std::ofstream &file, std::ofstream &log);
|
||||
};
|
||||
|
||||
}
|
||||
}
|
|
@ -1,91 +0,0 @@
|
|||
// 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 "Recorder.h"
|
||||
#include "RecorderFrames.h"
|
||||
#include "RecorderHelpers.h"
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
void RecorderFrame::read(std::ifstream &file) {
|
||||
//readValue<uint64_t>(file, this.id);
|
||||
//readValue<double>(file, this.durationThis);
|
||||
//readValue<double>(file, this.elapsed);
|
||||
readValue<RecorderFrame>(file, *this);
|
||||
}
|
||||
|
||||
void RecorderFrame::write(std::ofstream &file) {
|
||||
//writeValue<uint64_t>(file, frame.id);
|
||||
//writeValue<double>(file, frame.durationThis);
|
||||
//writeValue<double>(file, frame.elapsed);
|
||||
writeValue<RecorderFrame>(file, *this);
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
RecorderFrames::RecorderFrames(void) {
|
||||
reset();
|
||||
}
|
||||
|
||||
void RecorderFrames::reset(void) {
|
||||
frame.id = 0;
|
||||
frame.durationThis = 0.0f;
|
||||
frame.elapsed = 0.0f;
|
||||
lastTime = std::chrono::high_resolution_clock::now();
|
||||
offsetPreviousFrame = 0;
|
||||
}
|
||||
|
||||
void RecorderFrames::setFrame(void) {
|
||||
auto now = std::chrono::high_resolution_clock::now();
|
||||
|
||||
if (frame.id == 0) {
|
||||
frame.elapsed = 0.0f;
|
||||
frame.durationThis = 0.0f;
|
||||
}
|
||||
else
|
||||
{
|
||||
frame.durationThis = std::chrono::duration<double>(now - lastTime).count();
|
||||
frame.elapsed += frame.durationThis;
|
||||
}
|
||||
|
||||
lastTime = now;
|
||||
++frame.id;
|
||||
}
|
||||
|
||||
void RecorderFrames::write(std::ofstream &file, std::ofstream &log) {
|
||||
std::streampos pos, offset;
|
||||
double dummy = -1.0f;
|
||||
|
||||
// write the packet id
|
||||
writeValue<char>(file, static_cast<char>(RecorderPacketId::Frame));
|
||||
|
||||
// write the packet size
|
||||
uint32_t total = sizeof(RecorderFrame);
|
||||
writeValue<uint32_t>(file, total);
|
||||
|
||||
// write frame record
|
||||
writeValue<uint64_t>(file, frame.id);
|
||||
offset = file.tellp();
|
||||
writeValue<double>(file, dummy);
|
||||
writeValue<double>(file, frame.elapsed);
|
||||
|
||||
// we need to write this duration to previous frame
|
||||
if (offsetPreviousFrame > 0) {
|
||||
pos = file.tellp();
|
||||
file.seekp(offsetPreviousFrame, std::ios::beg);
|
||||
writeValue<double>(file, frame.durationThis);
|
||||
file.seekp(pos, std::ios::beg);
|
||||
}
|
||||
|
||||
// save position for next actualization
|
||||
offsetPreviousFrame = offset;
|
||||
|
||||
log << "frame " << frame.id << " elapsed " << frame.elapsed << "\n";
|
||||
}
|
||||
|
||||
}
|
||||
}
|
|
@ -1,42 +0,0 @@
|
|||
// 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 <chrono>
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct RecorderFrame {
|
||||
uint64_t id;
|
||||
double durationThis;
|
||||
double elapsed;
|
||||
|
||||
void read(std::ifstream &file);
|
||||
void write(std::ofstream &file);
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class RecorderFrames {
|
||||
|
||||
public:
|
||||
RecorderFrames(void);
|
||||
void reset();
|
||||
void setFrame(void);
|
||||
void write(std::ofstream &file, std::ofstream &log);
|
||||
|
||||
|
||||
private:
|
||||
RecorderFrame frame;
|
||||
std::streampos offsetPreviousFrame;
|
||||
std::chrono::time_point<std::chrono::high_resolution_clock> lastTime;
|
||||
};
|
||||
|
||||
}
|
||||
}
|
|
@ -1,107 +0,0 @@
|
|||
// 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 "RecorderHelpers.h"
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
// write binary data from Vector3D
|
||||
void writeVector3D(std::ofstream &file, const carla::geom::Vector3D &obj) {
|
||||
//file.write(reinterpret_cast<const char*>(&obj.x), sizeof(float));
|
||||
//file.write(reinterpret_cast<const char*>(&obj.y), sizeof(float));
|
||||
//file.write(reinterpret_cast<const char*>(&obj.z), sizeof(float));
|
||||
writeValue<float>(file, obj.x);
|
||||
writeValue<float>(file, obj.y);
|
||||
writeValue<float>(file, obj.z);
|
||||
}
|
||||
|
||||
// write binary data from Location
|
||||
void writeLocation(std::ofstream &file, const carla::geom::Location &obj) {
|
||||
//file.write(reinterpret_cast<const char*>(&obj.x), sizeof(float));
|
||||
//file.write(reinterpret_cast<const char*>(&obj.y), sizeof(float));
|
||||
//file.write(reinterpret_cast<const char*>(&obj.z), sizeof(float));
|
||||
writeValue<float>(file, obj.x);
|
||||
writeValue<float>(file, obj.y);
|
||||
writeValue<float>(file, obj.z);
|
||||
}
|
||||
|
||||
// write binary data from Rotation
|
||||
void writeRotation(std::ofstream &file, const carla::geom::Rotation &obj) {
|
||||
writeValue<float>(file, obj.pitch);
|
||||
writeValue<float>(file, obj.yaw);
|
||||
writeValue<float>(file, obj.roll);
|
||||
}
|
||||
|
||||
// write binary data from Transform
|
||||
void writeTransform(std::ofstream &file, const carla::geom::Transform &obj){
|
||||
writeLocation(file, obj.location);
|
||||
writeRotation(file, obj.rotation);
|
||||
}
|
||||
|
||||
// write binary data from string (length + text)
|
||||
void writeString(std::ofstream &file, const std::string &obj) {
|
||||
uint16_t length = obj.size();
|
||||
writeValue<uint16_t>(file, length);
|
||||
file.write(reinterpret_cast<const char*>(obj.c_str()), length);
|
||||
}
|
||||
|
||||
// write binary data from buffer (length + data)
|
||||
void writeBuffer(std::ofstream &file, const Buffer &obj) {
|
||||
uint16_t length = obj.size();
|
||||
writeValue<uint16_t>(file, length);
|
||||
file.write(reinterpret_cast<const char*>(obj.data()), length);
|
||||
}
|
||||
|
||||
// read binary data from Vector3D
|
||||
void readVector3D(std::ifstream &file, carla::geom::Vector3D &obj) {
|
||||
readValue<float>(file, obj.x);
|
||||
readValue<float>(file, obj.y);
|
||||
readValue<float>(file, obj.z);
|
||||
}
|
||||
|
||||
// read binary data from Location
|
||||
void readLocation(std::ifstream &file, carla::geom::Location &obj) {
|
||||
readValue<float>(file, obj.x);
|
||||
readValue<float>(file, obj.y);
|
||||
readValue<float>(file, obj.z);
|
||||
}
|
||||
|
||||
// read binary data from Rotation
|
||||
void readRotation(std::ifstream &file, carla::geom::Rotation &obj) {
|
||||
readValue<float>(file, obj.pitch);
|
||||
readValue<float>(file, obj.yaw);
|
||||
readValue<float>(file, obj.roll);
|
||||
}
|
||||
|
||||
// read binary data from Transform
|
||||
void readTransform(std::ifstream &file, carla::geom::Transform &obj){
|
||||
readLocation(file, obj.location);
|
||||
readRotation(file, obj.rotation);
|
||||
}
|
||||
|
||||
// read binary data from string (length + text)
|
||||
void readString(std::ifstream &file, std::string &obj) {
|
||||
uint16_t length;
|
||||
readValue<uint16_t>(file, length);
|
||||
if (length > 0) {
|
||||
obj.resize(length);
|
||||
file.read(&obj[0], length);
|
||||
}
|
||||
}
|
||||
|
||||
// read binary data to buffer (length + data)
|
||||
void readBuffer(std::ifstream &file, Buffer &obj) {
|
||||
uint16_t length;
|
||||
readValue<uint16_t>(file, length);
|
||||
if (length > 0) {
|
||||
obj.reset(static_cast<unsigned int>(length));
|
||||
file.read(reinterpret_cast<char *>(obj.data()), length);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
|
@ -1,68 +0,0 @@
|
|||
// 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 "carla/Buffer.h"
|
||||
#include "carla/geom/Vector3D.h"
|
||||
#include "carla/geom/Location.h"
|
||||
#include "carla/geom/Transform.h"
|
||||
#include "carla/geom/Rotation.h"
|
||||
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
//---------
|
||||
// recorder
|
||||
//---------
|
||||
|
||||
// write binary data (using sizeof())
|
||||
template<typename T>
|
||||
void writeValue(std::ofstream &file, const T &obj) {
|
||||
file.write(reinterpret_cast<const char*>(&obj), sizeof(T));
|
||||
}
|
||||
|
||||
// write binary data from Vector3D
|
||||
void writeVector3D(std::ofstream &file, const carla::geom::Vector3D &obj);
|
||||
// write binary data from Location
|
||||
void writeLocation(std::ofstream &file, const carla::geom::Location &obj);
|
||||
// write binary data from Transform
|
||||
void writeTransform(std::ofstream &file, const carla::geom::Transform &obj);
|
||||
// write binary data from Rotation
|
||||
void writeRotation(std::ofstream &file, const carla::geom::Rotation &obj);
|
||||
// write binary data from string (length + text)
|
||||
void writeString(std::ofstream &file, const std::string &obj);
|
||||
// write binary data from buffer (length + data)
|
||||
void writeBuffer(std::ofstream &file, const Buffer &obj);
|
||||
|
||||
//---------
|
||||
// replayer
|
||||
//---------
|
||||
|
||||
// read binary data (using sizeof())
|
||||
template<typename T>
|
||||
void readValue(std::ifstream &file, T &obj) {
|
||||
file.read(reinterpret_cast<char *>(&obj), sizeof(T));
|
||||
}
|
||||
|
||||
// read binary data from Vector3D
|
||||
void readVector3D(std::ifstream &file, carla::geom::Vector3D &obj);
|
||||
// read binary data from Location
|
||||
void readLocation(std::ifstream &file, carla::geom::Location &obj);
|
||||
// read binary data from Transform
|
||||
void readTransform(std::ifstream &file, carla::geom::Transform &obj);
|
||||
// read binary data from Rotation
|
||||
void readRotation(std::ifstream &file, carla::geom::Rotation &obj);
|
||||
// read binary data from string (length + text)
|
||||
void readString(std::ifstream &file, std::string &obj);
|
||||
// read binary data to buffer (length + data)
|
||||
void readBuffer(std::ifstream &file, Buffer &obj);
|
||||
|
||||
|
||||
}
|
||||
}
|
|
@ -1,40 +0,0 @@
|
|||
// 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 "carla/Buffer.h"
|
||||
#include "RecorderHelpers.h"
|
||||
|
||||
#include <fstream>
|
||||
#include <ctime>
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
struct RecorderInfo {
|
||||
uint16_t version;
|
||||
Buffer magic;
|
||||
std::time_t date;
|
||||
Buffer mapfile;
|
||||
|
||||
void read(std::ifstream &file) {
|
||||
readValue<uint16_t>(file, version);
|
||||
readBuffer(file, magic);
|
||||
readValue<std::time_t>(file, date);
|
||||
readBuffer(file, mapfile);
|
||||
}
|
||||
|
||||
void write(std::ofstream &file) {
|
||||
writeValue<uint16_t>(file, version);
|
||||
writeBuffer(file, magic);
|
||||
writeValue<std::time_t>(file, date);
|
||||
writeBuffer(file, mapfile);
|
||||
}
|
||||
};
|
||||
|
||||
}
|
||||
}
|
|
@ -1,76 +0,0 @@
|
|||
// 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 "Recorder.h"
|
||||
#include "RecorderPosition.h"
|
||||
#include "RecorderHelpers.h"
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
void RecorderPosition::write(std::ofstream &file) {
|
||||
// database id
|
||||
writeValue<uint32_t>(file, this->databaseId);
|
||||
// transform
|
||||
writeTransform(file, this->transform);
|
||||
// velocity
|
||||
// writeVector3D(file, this->velocity);
|
||||
// velocity
|
||||
// writeVector3D(file, this->angularVelocity);
|
||||
}
|
||||
void RecorderPosition::read(std::ifstream &file) {
|
||||
// database id
|
||||
readValue<uint32_t>(file, this->databaseId);
|
||||
// transform
|
||||
readTransform(file, this->transform);
|
||||
// velocity
|
||||
// readVector3D(file, this->velocity);
|
||||
// velocity
|
||||
// readVector3D(file, this->angularVelocity);
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
void RecorderPositions::clear(void) {
|
||||
positions.clear();
|
||||
}
|
||||
|
||||
void RecorderPositions::addPosition(const RecorderPosition &position) {
|
||||
positions.push_back(std::move(position));
|
||||
//log << "add position (" << sizeof(position) << ") " << position.transform.location.x << "," << position.transform.location.y << "," << position.transform.location.z << std::endl;
|
||||
//log << "add position for id." << position.id << std::endl;
|
||||
}
|
||||
|
||||
void RecorderPositions::write(std::ofstream &file, std::ofstream &log) {
|
||||
|
||||
// write the packet id
|
||||
writeValue<char>(file, static_cast<char>(RecorderPacketId::Position));
|
||||
|
||||
// write the packet size
|
||||
uint32_t total = 2 + positions.size() * sizeof(RecorderPosition);
|
||||
writeValue<uint32_t>(file, total);
|
||||
|
||||
// write total records
|
||||
total = positions.size();
|
||||
writeValue<short>(file, total);
|
||||
|
||||
// write records
|
||||
file.write(reinterpret_cast<const char*>(positions.data()), positions.size() * sizeof(RecorderPosition));
|
||||
/*
|
||||
// write records
|
||||
for (auto rec : positions) {
|
||||
writeValue<uint32_t>(file, rec.id); // actor id
|
||||
writeTransform(file, rec.transform); // transform
|
||||
writeVector3D(file, rec.velocity); // velocity
|
||||
writeVector3D(file, rec.angularVelocity); // angular velocity
|
||||
}
|
||||
*/
|
||||
|
||||
log << "write positions (" << positions.size() << " * " << sizeof(RecorderPosition) << ")\n";
|
||||
}
|
||||
|
||||
}
|
||||
}
|
|
@ -1,41 +0,0 @@
|
|||
// 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 "carla/geom/Vector3D.h"
|
||||
#include "carla/geom/Transform.h"
|
||||
#include <fstream>
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct RecorderPosition {
|
||||
uint32_t databaseId;
|
||||
carla::geom::Transform transform;
|
||||
// carla::geom::Vector3D velocity;
|
||||
// carla::geom::Vector3D angularVelocity;
|
||||
|
||||
void read(std::ifstream &file);
|
||||
void write(std::ofstream &file);
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class RecorderPositions {
|
||||
|
||||
public:
|
||||
RecorderPositions() = default;
|
||||
void addPosition(const RecorderPosition &_pos);
|
||||
void clear(void);
|
||||
void write(std::ofstream &file,std::ofstream &log);
|
||||
|
||||
private:
|
||||
std::vector<RecorderPosition> positions;
|
||||
};
|
||||
|
||||
}
|
||||
}
|
|
@ -1,73 +0,0 @@
|
|||
// 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 "Recorder.h"
|
||||
#include "RecorderState.h"
|
||||
#include "RecorderHelpers.h"
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
void RecorderStateTrafficLight::write(std::ofstream &file) {
|
||||
writeValue<uint32_t>(file, this->databaseId);
|
||||
writeValue<bool>(file, this->isFrozen);
|
||||
writeValue<float>(file, this->elapsedTime);
|
||||
writeValue<char>(file, this->state);
|
||||
}
|
||||
|
||||
void RecorderStateTrafficLight::read(std::ifstream &file) {
|
||||
readValue<uint32_t>(file, this->databaseId);
|
||||
readValue<bool>(file, this->isFrozen);
|
||||
readValue<float>(file, this->elapsedTime);
|
||||
readValue<char>(file, this->state);
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
void RecorderStates::clear(void) {
|
||||
statesTrafficLights.clear();
|
||||
}
|
||||
|
||||
void RecorderStates::addState(RecorderStateTrafficLight state) {
|
||||
statesTrafficLights.push_back(std::move(state));
|
||||
}
|
||||
|
||||
void RecorderStates::writeStatesTrafficLight(std::ofstream &file) {
|
||||
// write total records
|
||||
short total = statesTrafficLights.size();
|
||||
writeValue<short>(file, total);
|
||||
|
||||
for (unsigned long i=0; i<statesTrafficLights.size(); ++i) {
|
||||
statesTrafficLights[i].write(file);
|
||||
}
|
||||
}
|
||||
|
||||
void RecorderStates::write(std::ofstream &file, std::ofstream &log) {
|
||||
|
||||
// write the packet id
|
||||
writeValue<char>(file, static_cast<char>(RecorderPacketId::State));
|
||||
|
||||
std::streampos posStart = file.tellp();
|
||||
|
||||
// write a dummy packet size
|
||||
int total = 0;
|
||||
writeValue<int>(file, total);
|
||||
|
||||
// write events
|
||||
writeStatesTrafficLight(file);
|
||||
|
||||
// write the real packet size
|
||||
std::streampos posEnd = file.tellp();
|
||||
total = posEnd - posStart - sizeof(int);
|
||||
file.seekp(posStart, std::ios::beg);
|
||||
writeValue<int>(file, total);
|
||||
file.seekp(posEnd, std::ios::beg);
|
||||
|
||||
log << "write states (" << statesTrafficLights.size() << ")\n";
|
||||
}
|
||||
|
||||
}
|
||||
}
|
|
@ -1,44 +0,0 @@
|
|||
// 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 "carla/geom/Transform.h"
|
||||
#include <fstream>
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
#pragma pack(push, 1)
|
||||
|
||||
struct RecorderStateTrafficLight {
|
||||
uint32_t databaseId;
|
||||
bool isFrozen;
|
||||
float elapsedTime;
|
||||
char state;
|
||||
|
||||
void read(std::ifstream &file);
|
||||
void write(std::ofstream &file);
|
||||
};
|
||||
|
||||
#pragma pack(pop)
|
||||
|
||||
class RecorderStates {
|
||||
|
||||
public:
|
||||
RecorderStates() = default;
|
||||
void addState(const RecorderStateTrafficLight state);
|
||||
void clear(void);
|
||||
void write(std::ofstream &_file, std::ofstream &log);
|
||||
|
||||
private:
|
||||
std::vector<RecorderStateTrafficLight> statesTrafficLights;
|
||||
|
||||
void writeStatesTrafficLight(std::ofstream &file);
|
||||
};
|
||||
|
||||
}
|
||||
}
|
|
@ -1,581 +0,0 @@
|
|||
// 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 "Replayer.h"
|
||||
#include "Recorder.h"
|
||||
#include "carla/Logging.h"
|
||||
|
||||
#include <ctime>
|
||||
#include <sstream>
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
Replayer::Replayer() {
|
||||
}
|
||||
|
||||
Replayer::~Replayer() {
|
||||
stop();
|
||||
}
|
||||
|
||||
// callbacks
|
||||
void Replayer::setCallbackEventAdd(RecorderCallbackEventAdd f) {
|
||||
callbackEventAdd = std::move(f);
|
||||
}
|
||||
void Replayer::setCallbackEventDel(RecorderCallbackEventDel f) {
|
||||
callbackEventDel = std::move(f);
|
||||
}
|
||||
void Replayer::setCallbackEventParent(RecorderCallbackEventParent f) {
|
||||
callbackEventParent = std::move(f);
|
||||
}
|
||||
void Replayer::setCallbackEventPosition(RecorderCallbackPosition f) {
|
||||
callbackPosition = std::move(f);
|
||||
}
|
||||
void Replayer::setCallbackEventFinish(RecorderCallbackFinish f) {
|
||||
callbackFinish = std::move(f);
|
||||
}
|
||||
void Replayer::setCallbackStateTrafficLight(RecorderCallbackStateTrafficLight f) {
|
||||
callbackStateTrafficLight = std::move(f);
|
||||
}
|
||||
|
||||
void Replayer::stop(bool keepActors) {
|
||||
if (enabled) {
|
||||
enabled = false;
|
||||
if (!keepActors)
|
||||
processToTime(totalTime);
|
||||
file.close();
|
||||
// callback
|
||||
if (callbackFinish)
|
||||
callbackFinish(keepActors);
|
||||
}
|
||||
if (!keepActors)
|
||||
log_warning("Replayer stop");
|
||||
else
|
||||
log_warning("Replayer stop (keeping actors)");
|
||||
}
|
||||
|
||||
bool Replayer::readHeader() {
|
||||
if (file.eof()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
readValue<char>(file, header.id);
|
||||
readValue<uint32_t>(file, header.size);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void Replayer::skipPacket() {
|
||||
file.seekg(header.size, std::ios::cur);
|
||||
}
|
||||
|
||||
std::string Replayer::getInfo(std::string filename) {
|
||||
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;
|
||||
RecorderEventAdd eventAdd;
|
||||
RecorderEventDel eventDel;
|
||||
RecorderEventParent eventParent;
|
||||
// RecorderStateTrafficLight stateTraffic;
|
||||
bool bShowFrame;
|
||||
|
||||
// read info
|
||||
recInfo.read(file);
|
||||
|
||||
// check magic string
|
||||
std::string magic;
|
||||
magic.resize(recInfo.magic.size());
|
||||
std::copy(recInfo.magic.begin(), recInfo.magic.end(), magic.begin());
|
||||
if (magic != "CARLA_RECORDER") {
|
||||
info << "File is not a CARLA recorder" << std::endl;
|
||||
return info.str();
|
||||
}
|
||||
|
||||
// show general info
|
||||
info << "Version: " << recInfo.version << std::endl;
|
||||
info << "Map: " << recInfo.mapfile.data() << std::endl;
|
||||
tm *timeInfo = localtime(&recInfo.date);
|
||||
char dateStr[100];
|
||||
strftime(dateStr, 100, "%x %X", timeInfo);
|
||||
info << "Date: " << dateStr << std::endl << std::endl;
|
||||
|
||||
// parse only frames
|
||||
while (file) {
|
||||
// get header
|
||||
if (!readHeader()) {
|
||||
break;
|
||||
}
|
||||
|
||||
// check for a frame packet
|
||||
switch (header.id) {
|
||||
case static_cast<char>(RecorderPacketId::Frame):
|
||||
frame.read(file);
|
||||
// info << "Frame " << frame.id << " at " << frame.elapsed << "
|
||||
// seconds\n";
|
||||
break;
|
||||
|
||||
case static_cast<char>(RecorderPacketId::Event):
|
||||
bShowFrame = true;
|
||||
readValue<uint16_t>(file, total);
|
||||
if (total > 0 && bShowFrame) {
|
||||
info << "Frame " << frame.id << " at " << frame.elapsed << " seconds\n";
|
||||
bShowFrame = false;
|
||||
}
|
||||
for (i = 0; i < total; ++i) {
|
||||
eventAdd.read(file);
|
||||
// convert buffer to string to show
|
||||
std::string s("");
|
||||
s.resize(eventAdd.description.id.size());
|
||||
std::copy(eventAdd.description.id.begin(), eventAdd.description.id.end(), s.begin());
|
||||
info << " Create " << eventAdd.databaseId << ": " << s.data() << " (" <<
|
||||
eventAdd.description.uid << ") at (" << eventAdd.transform.location.x << ", " <<
|
||||
eventAdd.transform.location.y << ", " << eventAdd.transform.location.z << ")" << std::endl;
|
||||
for (auto &att : eventAdd.description.attributes) {
|
||||
std::string s1(""), s2("");
|
||||
s1.resize(att.id.size());
|
||||
std::copy(att.id.begin(), att.id.end(), s1.begin());
|
||||
s2.resize(att.value.size());
|
||||
std::copy(att.value.begin(), att.value.end(), s2.begin());
|
||||
info << " " << s1.data() << " = " << s2.data() << std::endl;
|
||||
}
|
||||
}
|
||||
readValue<uint16_t>(file, total);
|
||||
if (total > 0 && bShowFrame) {
|
||||
info << "Frame " << frame.id << " at " << frame.elapsed << " seconds\n";
|
||||
bShowFrame = false;
|
||||
}
|
||||
for (i = 0; i < total; ++i) {
|
||||
eventDel.read(file);
|
||||
info << " Destroy " << eventDel.databaseId << "\n";
|
||||
}
|
||||
readValue<uint16_t>(file, total);
|
||||
if (total > 0 && bShowFrame) {
|
||||
info << "Frame " << frame.id << " at " << frame.elapsed << " seconds\n";
|
||||
bShowFrame = false;
|
||||
}
|
||||
for (i = 0; i < total; ++i) {
|
||||
eventParent.read(file);
|
||||
info << " Parenting " << eventParent.databaseId << " with " << eventDel.databaseId <<
|
||||
" (parent)\n";
|
||||
}
|
||||
break;
|
||||
|
||||
case static_cast<char>(RecorderPacketId::Position):
|
||||
// info << "Positions\n";
|
||||
skipPacket();
|
||||
break;
|
||||
|
||||
case static_cast<char>(RecorderPacketId::State):
|
||||
skipPacket();
|
||||
// bShowFrame = true;
|
||||
// readValue<uint16_t>(file, total);
|
||||
//if (total > 0 && bShowFrame) {
|
||||
// info << "Frame " << frame.id << " at " << frame.elapsed << " seconds\n";
|
||||
// bShowFrame = false;
|
||||
//}
|
||||
//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;
|
||||
// }
|
||||
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();
|
||||
}
|
||||
|
||||
void Replayer::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);
|
||||
|
||||
// log_warning("Replayer rewind");
|
||||
}
|
||||
|
||||
// read last frame in file and return the total time recorded
|
||||
double Replayer::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>(RecorderPacketId::Frame):
|
||||
frame.read(file);
|
||||
break;
|
||||
default:
|
||||
skipPacket();
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
file.clear();
|
||||
file.seekg(current, std::ios::beg);
|
||||
return frame.elapsed;
|
||||
}
|
||||
|
||||
std::string Replayer::replayFile(std::string filename, double timeStart, double duration) {
|
||||
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);
|
||||
|
||||
// mark as enabled
|
||||
enabled = true;
|
||||
|
||||
return info.str();
|
||||
}
|
||||
|
||||
void Replayer::processToTime(double time) {
|
||||
double per = 0.0f;
|
||||
double newTime = currentTime + time;
|
||||
bool frameFound = false;
|
||||
|
||||
// check if we are in the right frame
|
||||
if (newTime >= frame.elapsed && newTime < frame.elapsed + frame.durationThis) {
|
||||
per = (newTime - frame.elapsed) / frame.durationThis;
|
||||
frameFound = true;
|
||||
}
|
||||
|
||||
// process all frames until time we want or end
|
||||
while (!file.eof() && !frameFound) {
|
||||
|
||||
// get header
|
||||
readHeader();
|
||||
// check it is a frame packet
|
||||
if (header.id != static_cast<char>(RecorderPacketId::Frame)) {
|
||||
if (!file.eof())
|
||||
log_error("Replayer file error: waitting for a Frame packet");
|
||||
stop();
|
||||
break;
|
||||
}
|
||||
// read current frame
|
||||
frame.read(file);
|
||||
|
||||
// check if target time is in this frame
|
||||
if (frame.elapsed + frame.durationThis < newTime) {
|
||||
per = 0.0f;
|
||||
} else {
|
||||
per = (newTime - frame.elapsed) / frame.durationThis;
|
||||
frameFound = true;
|
||||
}
|
||||
|
||||
// info << "Frame: " << frame.id << " (" << frame.durationThis << " / " <<
|
||||
// frame.elapsed << ") per: " << per << std::endl;
|
||||
|
||||
// get header
|
||||
readHeader();
|
||||
// check it is an events packet
|
||||
if (header.id != static_cast<char>(RecorderPacketId::Event)) {
|
||||
log_error("Replayer file error: waitting for an Event packet");
|
||||
stop();
|
||||
break;
|
||||
}
|
||||
processEvents();
|
||||
|
||||
// get header
|
||||
readHeader();
|
||||
// check it is a positions packet
|
||||
if (header.id != static_cast<char>(RecorderPacketId::Position)) {
|
||||
log_error("Replayer file error: waitting for a Position packet");
|
||||
stop();
|
||||
break;
|
||||
}
|
||||
if (frameFound) {
|
||||
processPositions();
|
||||
} else {
|
||||
skipPacket();
|
||||
}
|
||||
|
||||
// get header
|
||||
readHeader();
|
||||
// check it is an state packet
|
||||
if (header.id != static_cast<char>(RecorderPacketId::State)) {
|
||||
log_error("Replayer file error: waitting for an State packet");
|
||||
stop();
|
||||
break;
|
||||
}
|
||||
if (frameFound) {
|
||||
processStates();
|
||||
} else {
|
||||
skipPacket();
|
||||
}
|
||||
|
||||
// log_warning("Replayer new frame");
|
||||
}
|
||||
|
||||
// update all positions
|
||||
if (enabled && frameFound)
|
||||
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();
|
||||
else
|
||||
stop(true); // keep actors in scene so they continue with AI
|
||||
}
|
||||
}
|
||||
|
||||
void Replayer::processEvents(void) {
|
||||
uint16_t i, total;
|
||||
RecorderEventAdd eventAdd;
|
||||
RecorderEventDel eventDel;
|
||||
RecorderEventParent eventParent;
|
||||
std::stringstream info;
|
||||
|
||||
// create events
|
||||
readValue<uint16_t>(file, total);
|
||||
for (i = 0; i < total; ++i) {
|
||||
std::string s;
|
||||
eventAdd.read(file);
|
||||
|
||||
// avoid sensor events
|
||||
if (memcmp(eventAdd.description.id.data(), "sensor.", 7) != 0) {
|
||||
|
||||
// show log
|
||||
s.resize(eventAdd.description.id.size());
|
||||
std::copy(eventAdd.description.id.begin(), eventAdd.description.id.end(), s.begin());
|
||||
info.str("");
|
||||
info << "Create " << eventAdd.databaseId << " (" << eventAdd.description.uid << ") " << s.data() <<
|
||||
std::endl;
|
||||
for (const auto &att : eventAdd.description.attributes) {
|
||||
std::string s2;
|
||||
s.resize(att.id.size());
|
||||
std::copy(att.id.begin(), att.id.end(), s.begin());
|
||||
s2.resize(att.value.size());
|
||||
std::copy(att.value.begin(), att.value.end(), s2.begin());
|
||||
info << " " << s.data() << " = " << s2.data() << std::endl;
|
||||
}
|
||||
log_warning(info.str());
|
||||
|
||||
// callback
|
||||
if (callbackEventAdd) {
|
||||
// log_warning("calling callback add");
|
||||
auto result = callbackEventAdd(eventAdd.transform,
|
||||
std::move(eventAdd.description),
|
||||
eventAdd.databaseId);
|
||||
switch (result.first) {
|
||||
case 0:
|
||||
log_warning("actor could not be created");
|
||||
break;
|
||||
case 1:
|
||||
if (result.second != eventAdd.databaseId) {
|
||||
log_warning("actor created but with different id");
|
||||
}
|
||||
// mapping id (recorded Id is a new Id in replayer)
|
||||
mappedId[eventAdd.databaseId] = result.second;
|
||||
break;
|
||||
|
||||
case 2:
|
||||
log_warning("actor already exist, not created");
|
||||
// mapping id (say desired Id is mapped to what)
|
||||
mappedId[eventAdd.databaseId] = result.second;
|
||||
break;
|
||||
}
|
||||
|
||||
} else {
|
||||
log_warning("callback add is not defined");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// destroy events
|
||||
readValue<uint16_t>(file, total);
|
||||
for (i = 0; i < total; ++i) {
|
||||
eventDel.read(file);
|
||||
info.str("");
|
||||
info << "Destroy " << mappedId[eventDel.databaseId] << "\n";
|
||||
log_warning(info.str());
|
||||
// callback
|
||||
if (callbackEventDel) {
|
||||
callbackEventDel(mappedId[eventDel.databaseId]);
|
||||
mappedId.erase(eventDel.databaseId);
|
||||
} else {
|
||||
log_warning("callback del is not defined");
|
||||
}
|
||||
}
|
||||
|
||||
// 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[eventDel.databaseId] <<
|
||||
" (parent)\n";
|
||||
log_warning(info.str());
|
||||
// callback
|
||||
if (callbackEventParent) {
|
||||
callbackEventParent(mappedId[eventParent.databaseId], mappedId[eventParent.databaseIdParent]);
|
||||
} else {
|
||||
log_warning("callback parent is not defined");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Replayer::processStates(void) {
|
||||
uint16_t i, total;
|
||||
RecorderStateTrafficLight stateTrafficLight;
|
||||
std::stringstream info;
|
||||
|
||||
// read total traffic light states
|
||||
readValue<uint16_t>(file, total);
|
||||
for (i = 0; i < total; ++i) {
|
||||
stateTrafficLight.read(file);
|
||||
|
||||
// callback
|
||||
if (callbackStateTrafficLight) {
|
||||
// log_warning("calling callback add");
|
||||
stateTrafficLight.databaseId = mappedId[stateTrafficLight.databaseId];
|
||||
if (!callbackStateTrafficLight(stateTrafficLight))
|
||||
log_warning("callback state traffic light %d called but didn't work", stateTrafficLight.databaseId);
|
||||
} else {
|
||||
log_warning("callback state traffic light is not defined");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void Replayer::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) {
|
||||
RecorderPosition 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 Replayer::updatePositions(double per) {
|
||||
unsigned int i;
|
||||
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;
|
||||
}
|
||||
|
||||
// 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);
|
||||
// log_warning("Interpolation not possible, only one position");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// interpolate a position (transform, velocity...)
|
||||
void Replayer::interpolatePosition(
|
||||
const RecorderPosition &prevPos,
|
||||
const RecorderPosition &currPos,
|
||||
double per) {
|
||||
// call the callback
|
||||
callbackPosition(prevPos, currPos, per);
|
||||
}
|
||||
|
||||
// tick for the replayer
|
||||
void Replayer::tick(float delta) {
|
||||
// check if there are events to process
|
||||
if (enabled) {
|
||||
processToTime(delta);
|
||||
}
|
||||
|
||||
// log_warning("Replayer tick");
|
||||
}
|
||||
|
||||
} // namespace recorder
|
||||
} // namespace carla
|
|
@ -1,109 +0,0 @@
|
|||
// 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 <functional>
|
||||
#include "carla/NonCopyable.h"
|
||||
//#include "carla/recorder/Recorder.h"
|
||||
#include "carla/recorder/RecorderInfo.h"
|
||||
#include "carla/recorder/RecorderFrames.h"
|
||||
#include "carla/recorder/RecorderEvent.h"
|
||||
#include "carla/recorder/RecorderPosition.h"
|
||||
#include "carla/recorder/RecorderState.h"
|
||||
#include "carla/recorder/RecorderHelpers.h"
|
||||
|
||||
namespace carla {
|
||||
namespace recorder {
|
||||
|
||||
// callback prototypes
|
||||
typedef std::function<std::pair<int, uint32_t> (carla::geom::Transform, RecorderActorDescription, uint32_t uid)> RecorderCallbackEventAdd;
|
||||
typedef std::function<bool (uint32_t uid)> RecorderCallbackEventDel;
|
||||
typedef std::function<bool (uint32_t childId, uint32_t parentId)> RecorderCallbackEventParent;
|
||||
typedef std::function<bool (RecorderPosition pos1, RecorderPosition pos2, double per)> RecorderCallbackPosition;
|
||||
typedef std::function<bool (bool applyAutopilot)> RecorderCallbackFinish;
|
||||
typedef std::function<bool (RecorderStateTrafficLight state)> RecorderCallbackStateTrafficLight;
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct Header {
|
||||
char id;
|
||||
uint32_t size;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class Replayer : private NonCopyable {
|
||||
|
||||
public:
|
||||
|
||||
Replayer();
|
||||
~Replayer();
|
||||
|
||||
std::string getInfo(std::string filename);
|
||||
std::string replayFile(std::string filename, double timeStart = 0.0f, double duration = 0.0f);
|
||||
//void start(void);
|
||||
void stop(bool keepActors = false);
|
||||
|
||||
void enable(void);
|
||||
void disable(void);
|
||||
bool isEnabled(void) { return enabled; };
|
||||
|
||||
// callbacks
|
||||
void setCallbackEventAdd(RecorderCallbackEventAdd f);
|
||||
void setCallbackEventDel(RecorderCallbackEventDel f);
|
||||
void setCallbackEventParent(RecorderCallbackEventParent f);
|
||||
void setCallbackEventPosition(RecorderCallbackPosition f);
|
||||
void setCallbackEventFinish(RecorderCallbackFinish f);
|
||||
void setCallbackStateTrafficLight(RecorderCallbackStateTrafficLight f);
|
||||
|
||||
// tick for the replayer
|
||||
void tick(float time);
|
||||
|
||||
private:
|
||||
bool enabled;
|
||||
// binary file reader
|
||||
std::ifstream file;
|
||||
Header header;
|
||||
RecorderInfo recInfo;
|
||||
RecorderFrame frame;
|
||||
// callbacks
|
||||
RecorderCallbackEventAdd callbackEventAdd;
|
||||
RecorderCallbackEventDel callbackEventDel;
|
||||
RecorderCallbackEventParent callbackEventParent;
|
||||
RecorderCallbackPosition callbackPosition;
|
||||
RecorderCallbackFinish callbackFinish;
|
||||
RecorderCallbackStateTrafficLight callbackStateTrafficLight;
|
||||
// positions (to be able to interpolate)
|
||||
std::vector<RecorderPosition> currPos;
|
||||
std::vector<RecorderPosition> prevPos;
|
||||
// mapping id
|
||||
std::unordered_map<uint32_t, uint32_t> mappedId;
|
||||
// times
|
||||
double currentTime;
|
||||
double timeToStop;
|
||||
double totalTime;
|
||||
|
||||
// utils
|
||||
bool readHeader();
|
||||
void skipPacket();
|
||||
double getTotalTime(void);
|
||||
void rewind(void);
|
||||
|
||||
// processing packets
|
||||
void processToTime(double time);
|
||||
void processEvents(void);
|
||||
void processPositions(void);
|
||||
void processStates(void);
|
||||
|
||||
// positions
|
||||
void updatePositions(double per);
|
||||
void interpolatePosition(const RecorderPosition &start, const RecorderPosition &end, double per);
|
||||
|
||||
};
|
||||
|
||||
}
|
||||
}
|
|
@ -23,7 +23,7 @@ void export_client() {
|
|||
.def("get_server_version", CONST_CALL_WITHOUT_GIL(cc::Client, GetServerVersion))
|
||||
.def("get_world", &cc::Client::GetWorld)
|
||||
.def("start_recorder", &cc::Client::StartRecorder, (arg("name")))
|
||||
.def("stop_recorder", CALL_WITHOUT_GIL(cc::Client, StopRecorder))
|
||||
.def("stop_recorder", &cc::Client::StopRecorder)
|
||||
.def("show_recorder_file_info", &cc::Client::ShowRecorderFileInfo, (arg("name")))
|
||||
.def("replay_file", &cc::Client::ReplayFile, (arg("name"), arg("time_start"), arg("duration")))
|
||||
|
||||
|
|
|
@ -14,14 +14,11 @@
|
|||
#include "EngineUtils.h"
|
||||
#include "GameFramework/SpectatorPawn.h"
|
||||
|
||||
#include <compiler/disable-ue4-macros.h>
|
||||
#include <carla/recorder/Recorder.h>
|
||||
#include <compiler/enable-ue4-macros.h>
|
||||
|
||||
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");
|
||||
|
@ -49,7 +46,8 @@ UCarlaEpisode::UCarlaEpisode(const FObjectInitializer &ObjectInitializer)
|
|||
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;
|
||||
|
@ -66,7 +64,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;
|
||||
|
@ -80,12 +80,14 @@ void UCarlaEpisode::AttachActors(AActor *Child, AActor *Parent)
|
|||
Child->SetOwner(Parent);
|
||||
|
||||
// recorder event
|
||||
if (Recorder.isEnabled()) {
|
||||
crec::RecorderEventParent recEvent {
|
||||
if (Recorder->IsEnabled())
|
||||
{
|
||||
CarlaRecorderEventParent RecEvent
|
||||
{
|
||||
FindActor(Child).GetActorId(),
|
||||
FindActor(Parent).GetActorId()
|
||||
};
|
||||
Recorder.addEvent(std::move(recEvent));
|
||||
Recorder->AddEvent(std::move(RecEvent));
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -123,32 +125,36 @@ void UCarlaEpisode::InitializeAtBeginPlay()
|
|||
}
|
||||
|
||||
// replayer callbacks
|
||||
Recorder.getReplayer().setCallbackEventAdd([this](carla::geom::Transform transform,
|
||||
carla::recorder::RecorderActorDescription description, uint32_t desiredId) -> std::pair<int, uint32_t> {
|
||||
Recorder->GetReplayer()->SetCallbackEventAdd([this](FVector Location, FVector Rotation,
|
||||
CarlaRecorderActorDescription Description, uint32_t DesiredId) -> std::pair<int, uint32_t> {
|
||||
|
||||
FActorDescription ActorDesc;
|
||||
ActorDesc.UId = description.uid;
|
||||
ActorDesc.Id = FString(description.id.size(), UTF8_TO_TCHAR(description.id.data()));
|
||||
for (const auto &item : description.attributes) {
|
||||
FActorAttribute attr;
|
||||
attr.Type = static_cast<EActorAttributeType>(item.type);
|
||||
attr.Id = FString(item.id.size(), UTF8_TO_TCHAR(item.id.data()));
|
||||
attr.Value = FString(item.value.size(), UTF8_TO_TCHAR(item.value.data()));
|
||||
ActorDesc.Variations.Add(attr.Id, std::move(attr));
|
||||
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(transform, ActorDesc, desiredId);
|
||||
auto result = TryToCreateReplayerActor(Location, Rotation, ActorDesc, DesiredId);
|
||||
|
||||
if (result.first != 0) {
|
||||
if (result.first != 0)
|
||||
{
|
||||
// disable physics
|
||||
// SetActorSimulatePhysics(result.second, false);
|
||||
// disable autopilot
|
||||
auto Vehicle = Cast<ACarlaWheeledVehicle>(result.second.GetActor());
|
||||
if (Vehicle != nullptr) {
|
||||
if (Vehicle != nullptr)
|
||||
{
|
||||
auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController());
|
||||
if (Controller != nullptr) {
|
||||
if (Controller != nullptr)
|
||||
{
|
||||
Controller->SetAutopilot(false);
|
||||
UE_LOG(LogCarla, Log, TEXT("resetting autopilot to %d"), desiredId);
|
||||
UE_LOG(LogCarla, Log, TEXT("resetting autopilot to %d"), DesiredId);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -157,55 +163,62 @@ void UCarlaEpisode::InitializeAtBeginPlay()
|
|||
});
|
||||
|
||||
// callback
|
||||
Recorder.getReplayer().setCallbackEventDel([this](uint32_t databaseId) -> bool {
|
||||
auto actor = GetActorRegistry().Find(databaseId).GetActor();
|
||||
if (actor == nullptr) return false;
|
||||
Recorder->GetReplayer()->SetCallbackEventDel([this](uint32_t DatabaseId) -> bool {
|
||||
auto actor = GetActorRegistry().Find(DatabaseId).GetActor();
|
||||
if (actor == nullptr)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
DestroyActor(actor);
|
||||
return true;
|
||||
});
|
||||
|
||||
// callback
|
||||
Recorder.getReplayer().setCallbackEventParent([this](uint32_t childId, uint32_t parentId) -> bool {
|
||||
AActor *child = GetActorRegistry().Find(childId).GetActor();
|
||||
AActor *parent = GetActorRegistry().Find(parentId).GetActor();
|
||||
if (child && parent) {
|
||||
Recorder->GetReplayer()->SetCallbackEventParent([this](uint32_t ChildId, uint32_t ParentId) -> bool {
|
||||
AActor *child = GetActorRegistry().Find(ChildId).GetActor();
|
||||
AActor *parent = 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 {
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Parenting Actors not found"));
|
||||
return false;
|
||||
}
|
||||
});
|
||||
|
||||
// callback
|
||||
Recorder.getReplayer().setCallbackEventPosition([this](carla::recorder::RecorderPosition pos1,
|
||||
carla::recorder::RecorderPosition pos2, double per) -> bool {
|
||||
AActor *actor = GetActorRegistry().Find(pos1.databaseId).GetActor();
|
||||
Recorder->GetReplayer()->SetCallbackEventPosition([this](CarlaRecorderPosition Pos1,
|
||||
CarlaRecorderPosition Pos2, double Per) -> bool {
|
||||
AActor *actor = GetActorRegistry().Find(Pos1.DatabaseId).GetActor();
|
||||
if (actor && !actor->IsPendingKill())
|
||||
{
|
||||
// interpolate transform
|
||||
FVector location = FMath::Lerp(FVector(pos1.transform.location), FVector(pos2.transform.location), per);
|
||||
FRotator rotation = FMath::Lerp(FRotator(pos1.transform.rotation), FRotator(pos2.transform.rotation), per);
|
||||
FTransform trans(rotation, location, FVector(1,1,1));
|
||||
actor->SetActorRelativeTransform(trans, false, nullptr, ETeleportType::TeleportPhysics);
|
||||
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->SetActorRelativeTransform(Trans, false, nullptr, ETeleportType::TeleportPhysics);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
});
|
||||
|
||||
// callback
|
||||
Recorder.getReplayer().setCallbackStateTrafficLight([this](carla::recorder::RecorderStateTrafficLight state) -> bool {
|
||||
AActor *Actor = GetActorRegistry().Find(state.databaseId).GetActor();
|
||||
if (Actor && !Actor->IsPendingKill()) {
|
||||
Recorder->GetReplayer()->SetCallbackStateTrafficLight([this](CarlaRecorderStateTrafficLight State) -> bool {
|
||||
AActor *Actor = 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);
|
||||
TrafficLight->SetTrafficLightState(static_cast<ETrafficLightState>(State.State));
|
||||
TrafficLight->SetTimeIsFrozen(State.IsFrozen);
|
||||
TrafficLight->SetElapsedTime(State.ElapsedTime);
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
@ -213,22 +226,28 @@ void UCarlaEpisode::InitializeAtBeginPlay()
|
|||
});
|
||||
|
||||
// callback
|
||||
Recorder.getReplayer().setCallbackEventFinish([this](bool applyAutopilot) -> bool {
|
||||
Recorder->GetReplayer()->SetCallbackEventFinish([this](bool applyAutopilot) -> bool {
|
||||
if (!applyAutopilot)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
// set autopilo to all AI vehicles
|
||||
auto registry = GetActorRegistry();
|
||||
for (auto &&ActorView : registry) {
|
||||
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
|
||||
for (auto &&ActorView : registry)
|
||||
{
|
||||
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill())
|
||||
{
|
||||
continue;
|
||||
}
|
||||
auto Vehicle = Cast<ACarlaWheeledVehicle>(ActorView.GetActor());
|
||||
if (Vehicle == nullptr) {
|
||||
if (Vehicle == nullptr)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
// SetActorSimulatePhysics(ActorView, true);
|
||||
auto Controller = Cast<AWheeledVehicleAIController>(Vehicle->GetController());
|
||||
if (Controller == nullptr) {
|
||||
if (Controller == nullptr)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
Controller->SetAutopilot(true);
|
||||
|
@ -237,106 +256,93 @@ void UCarlaEpisode::InitializeAtBeginPlay()
|
|||
|
||||
return true;
|
||||
});
|
||||
|
||||
}
|
||||
|
||||
void UCarlaEpisode::EndPlay(void) {
|
||||
void UCarlaEpisode::EndPlay(void)
|
||||
{
|
||||
// stop recorder and replayer
|
||||
if (Recorder.isEnabled())
|
||||
Recorder.stop();
|
||||
if (Recorder.getReplayer().isEnabled())
|
||||
Recorder.getReplayer().stop();
|
||||
if (Recorder)
|
||||
{
|
||||
Recorder->Stop();
|
||||
if (Recorder->GetReplayer()->IsEnabled())
|
||||
{
|
||||
Recorder->GetReplayer()->Stop();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bool UCarlaEpisode::SetActorSimulatePhysics(FActorView &ActorView, bool bEnabled) {
|
||||
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill()) {
|
||||
bool UCarlaEpisode::SetActorSimulatePhysics(FActorView &ActorView, bool bEnabled)
|
||||
{
|
||||
if (!ActorView.IsValid() || ActorView.GetActor()->IsPendingKill())
|
||||
{
|
||||
return false;
|
||||
}
|
||||
auto RootComponent = Cast<UPrimitiveComponent>(ActorView.GetActor()->GetRootComponent());
|
||||
if (RootComponent == nullptr) {
|
||||
return false; // unable to set actor simulate physics: not supported by actor
|
||||
if (RootComponent == nullptr)
|
||||
{
|
||||
return false; // unable to set actor simulate physics: not supported by
|
||||
// actor
|
||||
}
|
||||
RootComponent->SetSimulatePhysics(bEnabled);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
std::string UCarlaEpisode::StartRecorder(std::string name) {
|
||||
std::string UCarlaEpisode::StartRecorder(std::string Name)
|
||||
{
|
||||
std::string result;
|
||||
FString Name2(Name.c_str());
|
||||
|
||||
// start
|
||||
result = Recorder.start(carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())), name, carla::rpc::FromFString(MapName));
|
||||
|
||||
// registring all existing actors in first frame
|
||||
FActorRegistry Registry = GetActorRegistry();
|
||||
for (auto &&View : Registry) {
|
||||
const AActor *actor = View.GetActor();
|
||||
check(actor != nullptr);
|
||||
// create event
|
||||
CreateRecorderEventAdd(
|
||||
View.GetActorId(),
|
||||
actor->GetActorTransform(),
|
||||
View.GetActorInfo()->Description
|
||||
);
|
||||
};
|
||||
if (Recorder)
|
||||
{
|
||||
result = Recorder->Start(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir()), Name2, MapName);
|
||||
}
|
||||
else
|
||||
{
|
||||
result = "Recorder is not ready";
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
void UCarlaEpisode::CreateRecorderEventAdd(
|
||||
uint32_t databaseId,
|
||||
const FTransform &Transform,
|
||||
FActorDescription thisActorDescription)
|
||||
{
|
||||
// convert from FActorDescription to crec::RecorderActorDescription
|
||||
crec::RecorderActorDescription description;
|
||||
description.uid = thisActorDescription.UId;
|
||||
description.id.copy_from(carla::rpc::FromFString(thisActorDescription.Id));
|
||||
|
||||
description.attributes.reserve(thisActorDescription.Variations.Num());
|
||||
for (const auto &item : thisActorDescription.Variations) {
|
||||
crec::RecorderActorAttribute attr;
|
||||
attr.type = static_cast<carla::rpc::ActorAttributeType>(item.Value.Type);
|
||||
attr.id.copy_from(carla::rpc::FromFString(item.Value.Id));
|
||||
attr.value.copy_from(carla::rpc::FromFString(item.Value.Value));
|
||||
// check for empty attributes
|
||||
if (attr.id.size() > 0)
|
||||
description.attributes.emplace_back(std::move(attr));
|
||||
}
|
||||
|
||||
// recorder event
|
||||
crec::RecorderEventAdd recEvent {
|
||||
databaseId,
|
||||
Transform,
|
||||
std::move(description)
|
||||
};
|
||||
Recorder.addEvent(std::move(recEvent));
|
||||
}
|
||||
|
||||
// create or reuse an actor for replaying
|
||||
std::pair<int, FActorView&> UCarlaEpisode::TryToCreateReplayerActor(carla::geom::Transform &transform, FActorDescription &ActorDesc, uint32_t desiredId) {
|
||||
std::pair<int, FActorView &> UCarlaEpisode::TryToCreateReplayerActor(
|
||||
FVector &Location,
|
||||
FVector &Rotation,
|
||||
FActorDescription &ActorDesc,
|
||||
uint32_t DesiredId)
|
||||
{
|
||||
FActorView view_empty;
|
||||
|
||||
// check type of actor we need
|
||||
if (ActorDesc.Id.StartsWith("traffic.")) {
|
||||
if (ActorDesc.Id.StartsWith("traffic."))
|
||||
{
|
||||
auto World = GetWorld();
|
||||
check(World != nullptr);
|
||||
// get its position (truncated as int's, and in Cm)
|
||||
int x = static_cast<int>(transform.location.x);
|
||||
int y = static_cast<int>(transform.location.y);
|
||||
int z = static_cast<int>(transform.location.z);
|
||||
UE_LOG(LogCarla, Log, TEXT("Trying to find traffic: %s (%d) [%d,%d,%d]"), *ActorDesc.Id, desiredId, x, y, z);
|
||||
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: %s (%d) [%d,%d,%d]"),
|
||||
*ActorDesc.Id,
|
||||
DesiredId,
|
||||
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 / 100.0f);
|
||||
int y2 = static_cast<int>(vec.Y / 100.0f);
|
||||
int z2 = static_cast<int>(vec.Z / 100.0f);
|
||||
// UE_LOG(LogCarla, Log, TEXT(" Checking with [%d,%d,%d]"), x2, y2, z2);
|
||||
if ((x2 == x) && (y2 == y) && (z2 == z)) {
|
||||
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
|
||||
auto view = ActorDispatcher->GetActorRegistry().Find(static_cast<AActor *>(Actor));
|
||||
// reuse that actor
|
||||
|
@ -347,30 +353,40 @@ std::pair<int, FActorView&> UCarlaEpisode::TryToCreateReplayerActor(carla::geom:
|
|||
// actor not found
|
||||
UE_LOG(LogCarla, Log, TEXT("Traffic not found"));
|
||||
return std::pair<int, FActorView &>(0, view_empty);
|
||||
} else if (ActorDesc.Id.StartsWith("vehicle.")) {
|
||||
}
|
||||
else if (ActorDesc.Id.StartsWith("vehicle."))
|
||||
{
|
||||
// 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 (GetActorRegistry().Contains(desiredId)) {
|
||||
auto view = GetActorRegistry().Find(desiredId);
|
||||
UE_LOG(LogCarla, Log, TEXT("Trying to create actor: %s (%d)"), *ActorDesc.Id, DesiredId);
|
||||
if (GetActorRegistry().Contains(DesiredId))
|
||||
{
|
||||
auto view = 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) {
|
||||
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));
|
||||
// create as new actor
|
||||
TPair<EActorSpawnResultStatus, FActorView> Result = SpawnActorWithInfo(transform, ActorDesc, desiredId);
|
||||
if (Result.Key == EActorSpawnResultStatus::Success) {
|
||||
TPair<EActorSpawnResultStatus, FActorView> Result = SpawnActorWithInfo(Trans, ActorDesc, DesiredId);
|
||||
if (Result.Key == EActorSpawnResultStatus::Success)
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Actor created by replayer with id %d"), Result.Value.GetActorId());
|
||||
return std::pair<int, FActorView &>(1, Result.Value);
|
||||
}
|
||||
else {
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Actor could't be created by replayer"));
|
||||
return std::pair<int, FActorView &>(0, Result.Value);
|
||||
}
|
||||
}
|
||||
else {
|
||||
else
|
||||
{
|
||||
// actor ignored
|
||||
return std::pair<int, FActorView &>(0, view_empty);
|
||||
}
|
||||
|
|
|
@ -10,21 +10,17 @@
|
|||
#include "Carla/Sensor/WorldObserver.h"
|
||||
#include "Carla/Weather/Weather.h"
|
||||
#include "Carla/Server/TheNewCarlaServer.h"
|
||||
#include "Carla/Game/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/recorder/Recorder.h>
|
||||
#include <carla/recorder/RecorderEvent.h>
|
||||
#include <carla/recorder/Replayer.h>
|
||||
#include <carla/streaming/Server.h>
|
||||
#include <compiler/enable-ue4-macros.h>
|
||||
|
||||
#include "CarlaEpisode.generated.h"
|
||||
|
||||
namespace crec = carla::recorder;
|
||||
|
||||
/// A simulation episode.
|
||||
///
|
||||
/// Each time the level is restarted a new episode is created.
|
||||
|
@ -152,16 +148,18 @@ public:
|
|||
FActorView::IdType DesiredId = 0)
|
||||
{
|
||||
auto result = ActorDispatcher->SpawnActor(Transform, thisActorDescription, DesiredId);
|
||||
|
||||
if (Recorder.isEnabled()) {
|
||||
if (result.Key == EActorSpawnResultStatus::Success) {
|
||||
CreateRecorderEventAdd(
|
||||
static_cast<carla::rpc::actor_id_type>(result.Value.GetActorId()),
|
||||
if (Recorder->IsEnabled())
|
||||
{
|
||||
if (result.Key == EActorSpawnResultStatus::Success)
|
||||
{
|
||||
Recorder->CreateRecorderEventAdd(
|
||||
result.Value.GetActorId(),
|
||||
Transform,
|
||||
std::move(thisActorDescription)
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
return result;
|
||||
}
|
||||
|
||||
|
@ -189,12 +187,14 @@ public:
|
|||
UFUNCTION(BlueprintCallable)
|
||||
bool DestroyActor(AActor *Actor)
|
||||
{
|
||||
if (Recorder.isEnabled()) {
|
||||
if (Recorder->IsEnabled())
|
||||
{
|
||||
// recorder event
|
||||
crec::RecorderEventDel recEvent {
|
||||
GetActorRegistry().Find(Actor).GetActorId(),
|
||||
CarlaRecorderEventDel RecEvent
|
||||
{
|
||||
GetActorRegistry().Find(Actor).GetActorId()
|
||||
};
|
||||
Recorder.addEvent(std::move(recEvent));
|
||||
Recorder->AddEvent(std::move(RecEvent));
|
||||
}
|
||||
|
||||
return ActorDispatcher->DestroyActor(Actor);
|
||||
|
@ -213,14 +213,19 @@ public:
|
|||
// -- Private methods and members --------------------------------------------
|
||||
// ===========================================================================
|
||||
|
||||
crec::Recorder &GetRecorder()
|
||||
ACarlaRecorder *GetRecorder()
|
||||
{
|
||||
return Recorder;
|
||||
}
|
||||
|
||||
crec::Replayer &GetReplayer()
|
||||
void SetRecorder(ACarlaRecorder *Rec)
|
||||
{
|
||||
return Recorder.getReplayer();
|
||||
Recorder = Rec;
|
||||
}
|
||||
|
||||
CarlaReplayer *GetReplayer()
|
||||
{
|
||||
return Recorder->GetReplayer();
|
||||
}
|
||||
|
||||
std::string StartRecorder(std::string name);
|
||||
|
@ -237,13 +242,9 @@ private:
|
|||
ActorDispatcher->Bind(ActorFactory);
|
||||
}
|
||||
|
||||
void CreateRecorderEventAdd(
|
||||
unsigned int databaseId,
|
||||
const FTransform &Transform,
|
||||
FActorDescription thisActorDescription);
|
||||
|
||||
std::pair<int, FActorView&> TryToCreateReplayerActor(
|
||||
carla::geom::Transform &transform,
|
||||
FVector &Location,
|
||||
FVector &Rotation,
|
||||
FActorDescription &ActorDesc,
|
||||
unsigned int desiredId);
|
||||
|
||||
|
@ -266,5 +267,5 @@ private:
|
|||
UPROPERTY(VisibleAnywhere)
|
||||
AWorldObserver *WorldObserver = nullptr;
|
||||
|
||||
crec::Recorder Recorder;
|
||||
ACarlaRecorder *Recorder = nullptr;
|
||||
};
|
||||
|
|
|
@ -0,0 +1,255 @@
|
|||
// 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 <ctime>
|
||||
#include <sstream>
|
||||
|
||||
ACarlaRecorder::ACarlaRecorder(void)
|
||||
{
|
||||
PrimaryActorTick.TickGroup = TG_PrePhysics;
|
||||
Disable();
|
||||
}
|
||||
|
||||
ACarlaRecorder::ACarlaRecorder(const FObjectInitializer &ObjectInitializer)
|
||||
: Super(ObjectInitializer)
|
||||
{
|
||||
PrimaryActorTick.TickGroup = TG_PrePhysics;
|
||||
Disable();
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Tick(float DeltaSeconds)
|
||||
{
|
||||
Super::Tick(DeltaSeconds);
|
||||
|
||||
// check if recording
|
||||
if (Enabled && Episode)
|
||||
{
|
||||
const FActorRegistry ® = Episode->GetActorRegistry();
|
||||
|
||||
// get positions
|
||||
for (TActorIterator<ACarlaWheeledVehicle> It(GetWorld()); It; ++It)
|
||||
{
|
||||
ACarlaWheeledVehicle *Actor = *It;
|
||||
check(Actor != nullptr);
|
||||
CarlaRecorderPosition recPos {
|
||||
reg.Find(Actor).GetActorId(),
|
||||
Actor->GetTransform().GetTranslation(),
|
||||
Actor->GetTransform().GetRotation().Euler()
|
||||
};
|
||||
AddPosition(recPos);
|
||||
}
|
||||
|
||||
// get states
|
||||
for (TActorIterator<ATrafficSignBase> It(GetWorld()); It; ++It)
|
||||
{
|
||||
ATrafficSignBase *Actor = *It;
|
||||
check(Actor != nullptr);
|
||||
auto TrafficLight = Cast<ATrafficLightBase>(Actor);
|
||||
if (TrafficLight != nullptr)
|
||||
{
|
||||
CarlaRecorderStateTrafficLight recTraffic {
|
||||
reg.Find(Actor).GetActorId(),
|
||||
TrafficLight->GetTimeIsFrozen(),
|
||||
TrafficLight->GetElapsedTime(),
|
||||
static_cast<char>(TrafficLight->GetTrafficLightState())
|
||||
};
|
||||
AddState(recTraffic);
|
||||
}
|
||||
}
|
||||
|
||||
// write all data for this frame
|
||||
Write();
|
||||
}
|
||||
else if (Episode && 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)
|
||||
{
|
||||
// reset
|
||||
Stop();
|
||||
|
||||
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())
|
||||
{
|
||||
// log_error("Recorder file couldn't be created");
|
||||
return "";
|
||||
}
|
||||
|
||||
// log file
|
||||
FString LogFilename = Path + Name + ".log";
|
||||
Log.open(TCHAR_TO_UTF8(*LogFilename));
|
||||
|
||||
// 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();
|
||||
}
|
||||
if (Log)
|
||||
{
|
||||
Log.close();
|
||||
}
|
||||
|
||||
Clear();
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Clear(void)
|
||||
{
|
||||
Events.Clear();
|
||||
Positions.Clear();
|
||||
States.Clear();
|
||||
|
||||
// log << "Clear\n";
|
||||
}
|
||||
|
||||
void ACarlaRecorder::Write(void)
|
||||
{
|
||||
// update this frame data
|
||||
Frames.SetFrame();
|
||||
|
||||
// write data
|
||||
Frames.Write(File, Log);
|
||||
Events.Write(File, Log);
|
||||
Positions.Write(File, Log);
|
||||
States.Write(File, Log);
|
||||
|
||||
Clear();
|
||||
// log << "Write\n";
|
||||
}
|
||||
|
||||
void ACarlaRecorder::AddPosition(const CarlaRecorderPosition &Position)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
Positions.AddPosition(Position);
|
||||
}
|
||||
}
|
||||
|
||||
void ACarlaRecorder::AddEvent(const CarlaRecorderEventAdd &Event)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
Events.AddEvent(std::move(Event));
|
||||
}
|
||||
}
|
||||
void ACarlaRecorder::AddEvent(const CarlaRecorderEventDel &Event)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
Events.AddEvent(std::move(Event));
|
||||
}
|
||||
}
|
||||
void ACarlaRecorder::AddEvent(const CarlaRecorderEventParent &Event)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
Events.AddEvent(std::move(Event));
|
||||
}
|
||||
}
|
||||
void ACarlaRecorder::AddState(const CarlaRecorderStateTrafficLight &State)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
States.AddState(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(),
|
||||
Actor->GetActorTransform(),
|
||||
View.GetActorInfo()->Description);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ACarlaRecorder::CreateRecorderEventAdd(
|
||||
unsigned int DatabaseId,
|
||||
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,
|
||||
Transform.GetTranslation(),
|
||||
Transform.GetRotation().Euler(),
|
||||
std::move(Description)
|
||||
};
|
||||
AddEvent(std::move(RecEvent));
|
||||
}
|
|
@ -0,0 +1,125 @@
|
|||
// 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 "Carla/Game/CarlaRecorderInfo.h"
|
||||
#include "Carla/Game/CarlaRecorderFrames.h"
|
||||
#include "Carla/Game/CarlaRecorderEvent.h"
|
||||
#include "Carla/Game/CarlaRecorderPosition.h"
|
||||
#include "Carla/Game/CarlaRecorderState.h"
|
||||
#include "Carla/Game/CarlaReplayer.h"
|
||||
#include "Carla/Actor/ActorDescription.h"
|
||||
|
||||
#include "CarlaRecorder.generated.h"
|
||||
|
||||
class AActor;
|
||||
class UCarlaEpisode;
|
||||
|
||||
enum class CarlaRecorderPacketId : uint8_t
|
||||
{
|
||||
Frame = 0,
|
||||
Event,
|
||||
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(void);
|
||||
|
||||
// events
|
||||
void AddEvent(const CarlaRecorderEventAdd &Event);
|
||||
|
||||
void AddEvent(const CarlaRecorderEventDel &Event);
|
||||
|
||||
void AddEvent(const CarlaRecorderEventParent &Event);
|
||||
|
||||
void AddPosition(const CarlaRecorderPosition &Position);
|
||||
|
||||
void AddState(const CarlaRecorderStateTrafficLight &State);
|
||||
|
||||
// set episode
|
||||
void SetEpisode(UCarlaEpisode *ThisEpisode)
|
||||
{
|
||||
Episode = ThisEpisode;
|
||||
}
|
||||
|
||||
void CreateRecorderEventAdd(
|
||||
unsigned int DatabaseId,
|
||||
const FTransform &Transform,
|
||||
FActorDescription ActorDescription);
|
||||
|
||||
// replayer
|
||||
CarlaReplayer *GetReplayer(void)
|
||||
{
|
||||
return &Replayer;
|
||||
}
|
||||
|
||||
std::string ShowFileInfo(std::string Path, std::string Name)
|
||||
{
|
||||
return Replayer.GetInfo(Path + Name);
|
||||
}
|
||||
std::string ReplayFile(std::string Path, std::string Name, double TimeStart, double Duration)
|
||||
{
|
||||
Stop();
|
||||
return Replayer.ReplayFile(Path + Name, TimeStart, Duration);
|
||||
}
|
||||
|
||||
// protected:
|
||||
|
||||
void Tick(float DeltaSeconds) final;
|
||||
|
||||
private:
|
||||
|
||||
bool Enabled; // enabled or not
|
||||
|
||||
// files
|
||||
std::ofstream File;
|
||||
std::ofstream Log;
|
||||
|
||||
UCarlaEpisode *Episode = nullptr;
|
||||
|
||||
// structures
|
||||
CarlaRecorderInfo Info;
|
||||
CarlaRecorderFrames Frames;
|
||||
CarlaRecorderEvents Events;
|
||||
CarlaRecorderPositions Positions;
|
||||
CarlaRecorderStates States;
|
||||
|
||||
// replayer
|
||||
CarlaReplayer Replayer;
|
||||
|
||||
void AddExistingActors(void);
|
||||
|
||||
};
|
|
@ -0,0 +1,184 @@
|
|||
// 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 "CarlaRecorderEvent.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
void CarlaRecorderEventAdd::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// OutLog << "add event: " << TCHAR_TO_UTF8(this->Description.Id) << " (id." << this->DatabaseId << ")\n";
|
||||
|
||||
// database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
|
||||
// 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);
|
||||
// OutLog << "Attributes: " << this->description.attributes.size() << std::endl;
|
||||
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);
|
||||
// log
|
||||
// OutLog << " " << TCHAR_TO_UTF8(this->Description.Attributes[i].Id) << " = " << TCHAR_TO_UTF8(this->Description.Attributes[i].Value) << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaRecorderEventAdd::Read(std::ifstream &InFile)
|
||||
{
|
||||
//OutLog << "add event: " << this->description.id.c_str() << " (id." << this->databaseId << ")\n";
|
||||
// database id
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId);
|
||||
|
||||
// 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);
|
||||
//OutLog << "Attributes: " << this->description.attributes.size() << std::endl;
|
||||
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));
|
||||
// log
|
||||
//OutLog << " " << att.id.c_str() << " = " << att.value.c_str() << std::endl;
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaRecorderEventDel::Read(std::ifstream &InFile)
|
||||
{
|
||||
// database id
|
||||
ReadValue<uint32_t>(InFile, this->DatabaseId);
|
||||
}
|
||||
void CarlaRecorderEventDel::Write(std::ofstream &OutFile)
|
||||
{
|
||||
// database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
}
|
||||
|
||||
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)
|
||||
{
|
||||
// database id
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseId);
|
||||
// database id parent
|
||||
WriteValue<uint32_t>(OutFile, this->DatabaseIdParent);
|
||||
}
|
||||
|
||||
//---------------------------------------------
|
||||
|
||||
void CarlaRecorderEvents::Clear(void)
|
||||
{
|
||||
EventsAdd.clear();
|
||||
EventsDel.clear();
|
||||
EventsParent.clear();
|
||||
}
|
||||
|
||||
void CarlaRecorderEvents::AddEvent(const CarlaRecorderEventAdd &Event)
|
||||
{
|
||||
EventsAdd.push_back(std::move(Event));
|
||||
}
|
||||
|
||||
void CarlaRecorderEvents::AddEvent(const CarlaRecorderEventDel &Event)
|
||||
{
|
||||
EventsDel.push_back(std::move(Event));
|
||||
}
|
||||
|
||||
void CarlaRecorderEvents::AddEvent(const CarlaRecorderEventParent &Event)
|
||||
{
|
||||
EventsParent.push_back(std::move(Event));
|
||||
}
|
||||
|
||||
void CarlaRecorderEvents::WriteEventsAdd(std::ofstream &OutFile)
|
||||
{
|
||||
// write total records
|
||||
uint16_t Total = EventsAdd.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
EventsAdd[i].Write(OutFile);
|
||||
}
|
||||
|
||||
void CarlaRecorderEvents::WriteEventsDel(std::ofstream &OutFile, std::ofstream &OutLog)
|
||||
{
|
||||
|
||||
// write total records
|
||||
uint16_t Total = EventsDel.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
{
|
||||
OutLog << "add del: " << EventsDel[i].DatabaseId << "\n";
|
||||
EventsDel[i].Write(OutFile);
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaRecorderEvents::WriteEventsParent(std::ofstream &OutFile, std::ofstream &OutLog)
|
||||
{
|
||||
// write total records
|
||||
uint16_t Total = EventsParent.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i=0; i<Total; ++i)
|
||||
{
|
||||
OutLog << "add parent: id." << EventsParent[i].DatabaseId << ", parent." << EventsParent[i].DatabaseIdParent << "\n";
|
||||
EventsParent[i].Write(OutFile);
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaRecorderEvents::Write(std::ofstream &OutFile, std::ofstream &OutLog)
|
||||
{
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::Event));
|
||||
|
||||
std::streampos PosStart = OutFile.tellp();
|
||||
|
||||
// write a dummy packet size
|
||||
uint32_t Total = 0;
|
||||
WriteValue<uint32_t>(OutFile, Total);
|
||||
|
||||
// write events
|
||||
WriteEventsAdd(OutFile);
|
||||
WriteEventsDel(OutFile, OutLog);
|
||||
WriteEventsParent(OutFile, OutLog);
|
||||
|
||||
// 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);
|
||||
|
||||
OutLog << "write events (" << EventsAdd.size() << "," << EventsDel.size() << "," << EventsParent.size() << ")\n";
|
||||
}
|
|
@ -0,0 +1,71 @@
|
|||
// 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;
|
||||
FVector Location;
|
||||
FVector Rotation;
|
||||
CarlaRecorderActorDescription Description;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
void Write(std::ofstream &OutFile);
|
||||
};
|
||||
|
||||
struct CarlaRecorderEventDel
|
||||
{
|
||||
uint32_t DatabaseId;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
void Write(std::ofstream &OutFile);
|
||||
};
|
||||
|
||||
struct CarlaRecorderEventParent
|
||||
{
|
||||
uint32_t DatabaseId;
|
||||
uint32_t DatabaseIdParent;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
void Write(std::ofstream &OutFile);
|
||||
};
|
||||
|
||||
class CarlaRecorderEvents {
|
||||
|
||||
public:
|
||||
void AddEvent(const CarlaRecorderEventAdd &Event);
|
||||
void AddEvent(const CarlaRecorderEventDel &Event);
|
||||
void AddEvent(const CarlaRecorderEventParent &Event);
|
||||
void Clear(void);
|
||||
void Write(std::ofstream &OutFile, std::ofstream &OutLog);
|
||||
|
||||
private:
|
||||
std::vector<CarlaRecorderEventAdd> EventsAdd;
|
||||
std::vector<CarlaRecorderEventDel> EventsDel;
|
||||
std::vector<CarlaRecorderEventParent> EventsParent;
|
||||
|
||||
void WriteEventsAdd(std::ofstream &OutFile);
|
||||
void WriteEventsDel(std::ofstream &OutFile, std::ofstream &OutLog);
|
||||
void WriteEventsParent(std::ofstream &OutFile, std::ofstream &OutLog);
|
||||
};
|
|
@ -0,0 +1,87 @@
|
|||
// 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;
|
||||
LastTime = std::chrono::high_resolution_clock::now();
|
||||
OffsetPreviousFrame = 0;
|
||||
}
|
||||
|
||||
void CarlaRecorderFrames::SetFrame(void)
|
||||
{
|
||||
auto Now = std::chrono::high_resolution_clock::now();
|
||||
|
||||
if (Frame.Id == 0)
|
||||
{
|
||||
Frame.Elapsed = 0.0f;
|
||||
Frame.DurationThis = 0.0f;
|
||||
}
|
||||
else
|
||||
{
|
||||
Frame.DurationThis = std::chrono::duration<double>(Now - LastTime).count();
|
||||
Frame.Elapsed += Frame.DurationThis;
|
||||
}
|
||||
|
||||
LastTime = Now;
|
||||
++Frame.Id;
|
||||
}
|
||||
|
||||
void CarlaRecorderFrames::Write(std::ofstream &OutFile, std::ofstream &OutLog)
|
||||
{
|
||||
std::streampos Pos, Offset;
|
||||
double Dummy = -1.0f;
|
||||
|
||||
// write the packet id
|
||||
WriteValue<char>(OutFile, static_cast<char>(CarlaRecorderPacketId::Frame));
|
||||
|
||||
// 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;
|
||||
|
||||
OutLog << "frame " << Frame.Id << " elapsed " << Frame.Elapsed << "\n";
|
||||
}
|
|
@ -0,0 +1,43 @@
|
|||
// 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 <chrono>
|
||||
|
||||
#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(void);
|
||||
|
||||
void Write(std::ofstream &OutFile, std::ofstream &OutLog);
|
||||
|
||||
private:
|
||||
|
||||
CarlaRecorderFrame Frame;
|
||||
std::streampos OffsetPreviousFrame;
|
||||
std::chrono::time_point<std::chrono::high_resolution_clock> LastTime;
|
||||
};
|
|
@ -0,0 +1,87 @@
|
|||
// 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);
|
||||
// CarlaRecorderHelperBuffer.push_back(0);
|
||||
// read
|
||||
InFile.read(reinterpret_cast<char *>(CarlaRecorderHelperBuffer.data()), Length);
|
||||
// convert from UTF8 to FString
|
||||
// OutObj = BytesToString(reinterpret_cast<uint8_t
|
||||
// *>(UTF8_TO_TCHAR(CarlaRecorderHelperBuffer.data())), Length);
|
||||
// OutObj = BytesToString(reinterpret_cast<uint8_t
|
||||
// *>(CarlaRecorderHelperBuffer.data()), Length);
|
||||
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,61 @@
|
|||
// 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::AddPosition(const CarlaRecorderPosition &Position)
|
||||
{
|
||||
Positions.push_back(Position);
|
||||
}
|
||||
|
||||
void CarlaRecorderPositions::Write(std::ofstream &OutFile, std::ofstream &OutLog)
|
||||
{
|
||||
// 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));
|
||||
}
|
||||
|
||||
OutLog << "write positions (" << Positions.size() << " * " << sizeof(CarlaRecorderPosition) << ")\n";
|
||||
}
|
|
@ -0,0 +1,41 @@
|
|||
// 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;
|
||||
// FVector Velocity;
|
||||
// FVector AngularVelocity;
|
||||
|
||||
void Read(std::ifstream &InFile);
|
||||
|
||||
void Write(std::ofstream &OutFile);
|
||||
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class CarlaRecorderPositions
|
||||
{
|
||||
public:
|
||||
|
||||
void AddPosition(const CarlaRecorderPosition &InObj);
|
||||
|
||||
void Clear(void);
|
||||
|
||||
void Write(std::ofstream &OutFile, std::ofstream &OutLog);
|
||||
|
||||
private:
|
||||
|
||||
std::vector<CarlaRecorderPosition> Positions;
|
||||
};
|
|
@ -0,0 +1,64 @@
|
|||
// 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::AddState(const CarlaRecorderStateTrafficLight &State)
|
||||
{
|
||||
StatesTrafficLights.push_back(std::move(State));
|
||||
}
|
||||
|
||||
void CarlaRecorderStates::WriteStatesTrafficLight(std::ofstream &OutFile)
|
||||
{
|
||||
// write total records
|
||||
uint16_t Total = StatesTrafficLights.size();
|
||||
WriteValue<uint16_t>(OutFile, Total);
|
||||
|
||||
for (uint16_t i = 0; i < Total; ++i)
|
||||
{
|
||||
StatesTrafficLights[i].Write(OutFile);
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaRecorderStates::Write(std::ofstream &OutFile, std::ofstream &OutLog)
|
||||
{
|
||||
// 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 events
|
||||
WriteStatesTrafficLight(OutFile);
|
||||
|
||||
OutLog << "write states (" << StatesTrafficLights.size() << ")\n";
|
||||
}
|
|
@ -0,0 +1,45 @@
|
|||
// 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 AddState(const CarlaRecorderStateTrafficLight &State);
|
||||
|
||||
void Clear(void);
|
||||
|
||||
void Write(std::ofstream &OutFile, std::ofstream &OutLog);
|
||||
|
||||
private:
|
||||
|
||||
std::vector<CarlaRecorderStateTrafficLight> StatesTrafficLights;
|
||||
|
||||
void WriteStatesTrafficLight(std::ofstream &OutFile);
|
||||
|
||||
};
|
|
@ -0,0 +1,683 @@
|
|||
// 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>
|
||||
|
||||
CarlaReplayer::CarlaReplayer()
|
||||
{}
|
||||
|
||||
CarlaReplayer::~CarlaReplayer()
|
||||
{
|
||||
Stop();
|
||||
}
|
||||
|
||||
// callbacks
|
||||
void CarlaReplayer::SetCallbackEventAdd(CarlaRecorderCallbackEventAdd f)
|
||||
{
|
||||
CallbackEventAdd = std::move(f);
|
||||
}
|
||||
void CarlaReplayer::SetCallbackEventDel(CarlaRecorderCallbackEventDel f)
|
||||
{
|
||||
CallbackEventDel = std::move(f);
|
||||
}
|
||||
void CarlaReplayer::SetCallbackEventParent(CarlaRecorderCallbackEventParent f)
|
||||
{
|
||||
CallbackEventParent = std::move(f);
|
||||
}
|
||||
void CarlaReplayer::SetCallbackEventPosition(CarlaRecorderCallbackPosition f)
|
||||
{
|
||||
CallbackPosition = std::move(f);
|
||||
}
|
||||
void CarlaReplayer::SetCallbackEventFinish(CarlaRecorderCallbackFinish f)
|
||||
{
|
||||
CallbackFinish = std::move(f);
|
||||
}
|
||||
void CarlaReplayer::SetCallbackStateTrafficLight(CarlaRecorderCallbackStateTrafficLight f)
|
||||
{
|
||||
CallbackStateTrafficLight = std::move(f);
|
||||
}
|
||||
|
||||
void CarlaReplayer::Stop(bool KeepActors)
|
||||
{
|
||||
if (Enabled)
|
||||
{
|
||||
Enabled = false;
|
||||
|
||||
// destroy actors if event was recorded?
|
||||
if (!KeepActors)
|
||||
{
|
||||
ProcessToTime(TotalTime);
|
||||
}
|
||||
|
||||
File.close();
|
||||
|
||||
// callback
|
||||
if (CallbackFinish)
|
||||
{
|
||||
CallbackFinish(KeepActors);
|
||||
}
|
||||
}
|
||||
// if (!KeepActors)
|
||||
// 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);
|
||||
}
|
||||
|
||||
std::string CarlaReplayer::GetInfo(std::string Filename)
|
||||
{
|
||||
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;
|
||||
CarlaRecorderEventAdd EventAdd;
|
||||
CarlaRecorderEventDel EventDel;
|
||||
CarlaRecorderEventParent EventParent;
|
||||
// CarlaRecorderStateTrafficLight StateTraffic;
|
||||
bool bShowFrame;
|
||||
|
||||
// read Info
|
||||
RecInfo.Read(File);
|
||||
|
||||
// check magic string
|
||||
// Info << "Checking Magic: " << TCHAR_TO_UTF8(*RecInfo.Magic) << std::endl;
|
||||
if (RecInfo.Magic != "CARLA_RECORDER")
|
||||
{
|
||||
Info << "File is not a CARLA recorder" << std::endl;
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
// 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, 100, "%x %X", TimeInfo);
|
||||
Info << "Date: " << DateStr << std::endl << std::endl;
|
||||
|
||||
// parse only frames
|
||||
while (File)
|
||||
{
|
||||
|
||||
// get header
|
||||
if (!ReadHeader())
|
||||
{
|
||||
break;
|
||||
}
|
||||
|
||||
// check for a frame packet
|
||||
switch (Header.Id)
|
||||
{
|
||||
case static_cast<char>(CarlaRecorderPacketId::Frame):
|
||||
Frame.Read(File);
|
||||
// Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds
|
||||
// (offset 0x" << std::hex << File.tellg() << std::dec << ")\n";
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::Event):
|
||||
bShowFrame = true;
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && bShowFrame)
|
||||
{
|
||||
Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n";
|
||||
bShowFrame = false;
|
||||
}
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
// add
|
||||
EventAdd.Read(File);
|
||||
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;
|
||||
}
|
||||
}
|
||||
// del
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && bShowFrame)
|
||||
{
|
||||
Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n";
|
||||
bShowFrame = false;
|
||||
}
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventDel.Read(File);
|
||||
Info << " Destroy " << EventDel.DatabaseId << "\n";
|
||||
}
|
||||
// parenting
|
||||
ReadValue<uint16_t>(File, Total);
|
||||
if (Total > 0 && bShowFrame)
|
||||
{
|
||||
Info << "Frame " << Frame.Id << " at " << Frame.Elapsed << " seconds\n";
|
||||
bShowFrame = false;
|
||||
}
|
||||
for (i = 0; i < Total; ++i)
|
||||
{
|
||||
EventParent.Read(File);
|
||||
Info << " Parenting " << EventParent.DatabaseId << " with " << EventDel.DatabaseId <<
|
||||
" (parent)\n";
|
||||
}
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::Position):
|
||||
// Info << "Positions\n";
|
||||
SkipPacket();
|
||||
break;
|
||||
|
||||
case static_cast<char>(CarlaRecorderPacketId::State):
|
||||
SkipPacket();
|
||||
// bShowFrame = true;
|
||||
// readValue<uint16_t>(File, Total);
|
||||
// if (Total > 0 && bShowFrame) {
|
||||
// Info << "Frame " << frame.id << " at " << frame.Elapsed << "
|
||||
// seconds\n";
|
||||
// bShowFrame = false;
|
||||
// }
|
||||
// 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;
|
||||
// }
|
||||
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();
|
||||
}
|
||||
|
||||
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::Frame):
|
||||
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)
|
||||
{
|
||||
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);
|
||||
|
||||
// mark as enabled
|
||||
Enabled = true;
|
||||
|
||||
return Info.str();
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessToTime(double Time)
|
||||
{
|
||||
double Per = 0.0f;
|
||||
double NewTime = CurrentTime + Time;
|
||||
bool bFrameFound = 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;
|
||||
}
|
||||
|
||||
// process all frames until time we want or end
|
||||
while (!File.eof() && !bFrameFound)
|
||||
{
|
||||
// get header
|
||||
ReadHeader();
|
||||
// check it is a frame packet
|
||||
if (Header.Id != static_cast<char>(CarlaRecorderPacketId::Frame))
|
||||
{
|
||||
if (!File.eof())
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Replayer File error: waitting for a Frame packet"));
|
||||
}
|
||||
Stop();
|
||||
break;
|
||||
}
|
||||
// read current frame
|
||||
Frame.Read(File);
|
||||
|
||||
// check if target time is in this frame
|
||||
if (Frame.Elapsed + Frame.DurationThis < NewTime)
|
||||
{
|
||||
Per = 0.0f;
|
||||
}
|
||||
else
|
||||
{
|
||||
Per = (NewTime - Frame.Elapsed) / Frame.DurationThis;
|
||||
bFrameFound = true;
|
||||
}
|
||||
|
||||
// Info << "Frame: " << Frame.id << " (" << Frame.DurationThis << " / " <<
|
||||
// Frame.Elapsed << ") per: " << Per << std::endl;
|
||||
|
||||
// get header
|
||||
ReadHeader();
|
||||
// check it is an events packet
|
||||
if (Header.Id != static_cast<char>(CarlaRecorderPacketId::Event))
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Replayer File error: waitting for an Event packet"));
|
||||
Stop();
|
||||
break;
|
||||
}
|
||||
ProcessEvents();
|
||||
|
||||
// get header
|
||||
ReadHeader();
|
||||
// check it is a positions packet
|
||||
if (Header.Id != static_cast<char>(CarlaRecorderPacketId::Position))
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Replayer File error: waitting for a Position packet"));
|
||||
Stop();
|
||||
break;
|
||||
}
|
||||
if (bFrameFound)
|
||||
{
|
||||
ProcessPositions();
|
||||
}
|
||||
else
|
||||
{
|
||||
SkipPacket();
|
||||
}
|
||||
|
||||
// get header
|
||||
ReadHeader();
|
||||
// check it is an state packet
|
||||
if (Header.Id != static_cast<char>(CarlaRecorderPacketId::State))
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("Replayer File error: waitting for an State packet"));
|
||||
Stop();
|
||||
break;
|
||||
}
|
||||
if (bFrameFound)
|
||||
{
|
||||
ProcessStates();
|
||||
}
|
||||
else
|
||||
{
|
||||
SkipPacket();
|
||||
}
|
||||
|
||||
// UE_LOG(LogCarla, Log, TEXT("Replayer new frame"));
|
||||
}
|
||||
|
||||
// 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();
|
||||
}
|
||||
else
|
||||
{
|
||||
Stop(true); // keep actors in scene so they continue with AI
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void CarlaReplayer::ProcessEvents(void)
|
||||
{
|
||||
uint16_t i, Total;
|
||||
CarlaRecorderEventAdd EventAdd;
|
||||
CarlaRecorderEventDel EventDel;
|
||||
CarlaRecorderEventParent EventParent;
|
||||
std::stringstream Info;
|
||||
|
||||
// create 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());
|
||||
|
||||
// callback
|
||||
if (CallbackEventAdd)
|
||||
{
|
||||
// UE_LOG(LogCarla, Log, TEXT("calling callback add"));
|
||||
auto Result = CallbackEventAdd(
|
||||
EventAdd.Location,
|
||||
EventAdd.Rotation,
|
||||
std::move(EventAdd.Description),
|
||||
EventAdd.DatabaseId);
|
||||
switch (Result.first)
|
||||
{
|
||||
case 0:
|
||||
UE_LOG(LogCarla, Log, TEXT("actor could not be created"));
|
||||
break;
|
||||
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;
|
||||
|
||||
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;
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("callback add is not defined"));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// 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());
|
||||
// callback
|
||||
if (CallbackEventDel)
|
||||
{
|
||||
CallbackEventDel(MappedId[EventDel.DatabaseId]);
|
||||
MappedId.erase(EventDel.DatabaseId);
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("callback del is not defined"));
|
||||
}
|
||||
}
|
||||
|
||||
// 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[EventDel.DatabaseId] <<
|
||||
" (parent)\n";
|
||||
// UE_LOG(LogCarla, Log, "%s", Info.str().c_str());
|
||||
// callback
|
||||
if (CallbackEventParent)
|
||||
{
|
||||
CallbackEventParent(MappedId[EventParent.DatabaseId], MappedId[EventParent.DatabaseIdParent]);
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("callback parent is not defined"));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
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);
|
||||
|
||||
// callback
|
||||
if (CallbackStateTrafficLight)
|
||||
{
|
||||
// UE_LOG(LogCarla, Log, TEXT("calling callback add"));
|
||||
StateTrafficLight.DatabaseId = MappedId[StateTrafficLight.DatabaseId];
|
||||
if (!CallbackStateTrafficLight(StateTrafficLight))
|
||||
{
|
||||
UE_LOG(LogCarla,
|
||||
Log,
|
||||
TEXT("callback state traffic light %d called but didn't work"),
|
||||
StateTrafficLight.DatabaseId);
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
UE_LOG(LogCarla, Log, TEXT("callback state traffic light is not defined"));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
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;
|
||||
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;
|
||||
}
|
||||
|
||||
// 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);
|
||||
// UE_LOG(LogCarla, Log, TEXT("Interpolation not possible, only one
|
||||
// position"));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// interpolate a position (transform, velocity...)
|
||||
void CarlaReplayer::InterpolatePosition(
|
||||
const CarlaRecorderPosition &Pos1,
|
||||
const CarlaRecorderPosition &Pos2,
|
||||
double Per)
|
||||
{
|
||||
// call the callback
|
||||
if (CallbackPosition)
|
||||
{
|
||||
CallbackPosition(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,126 @@
|
|||
// 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 "CarlaRecorderEvent.h"
|
||||
#include "CarlaRecorderPosition.h"
|
||||
#include "CarlaRecorderState.h"
|
||||
#include "CarlaRecorderHelpers.h"
|
||||
|
||||
// callback prototypes
|
||||
typedef std::function<std::pair<int, uint32_t>(FVector Location, FVector Rotation,
|
||||
CarlaRecorderActorDescription Desc, uint32_t UId)> CarlaRecorderCallbackEventAdd;
|
||||
typedef std::function<bool (uint32_t UId)> CarlaRecorderCallbackEventDel;
|
||||
typedef std::function<bool (uint32_t ChildId, uint32_t ParentId)> CarlaRecorderCallbackEventParent;
|
||||
typedef std::function<bool (CarlaRecorderPosition Pos1, CarlaRecorderPosition Pos2,
|
||||
double Per)> CarlaRecorderCallbackPosition;
|
||||
typedef std::function<bool (bool ApplyAutopilot)> CarlaRecorderCallbackFinish;
|
||||
typedef std::function<bool (CarlaRecorderStateTrafficLight State)> CarlaRecorderCallbackStateTrafficLight;
|
||||
|
||||
#pragma pack(push, 1)
|
||||
struct OHeader
|
||||
{
|
||||
char Id;
|
||||
uint32_t Size;
|
||||
};
|
||||
#pragma pack(pop)
|
||||
|
||||
class CarlaReplayer
|
||||
{
|
||||
public:
|
||||
|
||||
CarlaReplayer();
|
||||
~CarlaReplayer();
|
||||
|
||||
std::string GetInfo(std::string Filename);
|
||||
|
||||
std::string ReplayFile(std::string Filename, double TimeStart = 0.0f, double Duration = 0.0f);
|
||||
|
||||
// void Start(void);
|
||||
void Stop(bool KeepActors = false);
|
||||
|
||||
void Enable(void);
|
||||
|
||||
void Disable(void);
|
||||
|
||||
bool IsEnabled(void)
|
||||
{
|
||||
return Enabled;
|
||||
}
|
||||
|
||||
// callbacks
|
||||
void SetCallbackEventAdd(CarlaRecorderCallbackEventAdd f);
|
||||
|
||||
void SetCallbackEventDel(CarlaRecorderCallbackEventDel f);
|
||||
|
||||
void SetCallbackEventParent(CarlaRecorderCallbackEventParent f);
|
||||
|
||||
void SetCallbackEventPosition(CarlaRecorderCallbackPosition f);
|
||||
|
||||
void SetCallbackEventFinish(CarlaRecorderCallbackFinish f);
|
||||
|
||||
void SetCallbackStateTrafficLight(CarlaRecorderCallbackStateTrafficLight f);
|
||||
|
||||
// tick for the replayer
|
||||
void Tick(float Time);
|
||||
|
||||
private:
|
||||
|
||||
bool Enabled;
|
||||
// binary file reader
|
||||
std::ifstream File;
|
||||
OHeader Header;
|
||||
CarlaRecorderInfo RecInfo;
|
||||
CarlaRecorderFrame Frame;
|
||||
// callbacks
|
||||
CarlaRecorderCallbackEventAdd CallbackEventAdd;
|
||||
CarlaRecorderCallbackEventDel CallbackEventDel;
|
||||
CarlaRecorderCallbackEventParent CallbackEventParent;
|
||||
CarlaRecorderCallbackPosition CallbackPosition;
|
||||
CarlaRecorderCallbackFinish CallbackFinish;
|
||||
CarlaRecorderCallbackStateTrafficLight CallbackStateTrafficLight;
|
||||
// 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;
|
||||
|
||||
// utils
|
||||
bool ReadHeader();
|
||||
|
||||
void SkipPacket();
|
||||
|
||||
double GetTotalTime(void);
|
||||
|
||||
void Rewind(void);
|
||||
|
||||
// processing packets
|
||||
void ProcessToTime(double Time);
|
||||
|
||||
void ProcessEvents(void);
|
||||
|
||||
void ProcessPositions(void);
|
||||
|
||||
void ProcessStates(void);
|
||||
|
||||
// positions
|
||||
void UpdatePositions(double Per);
|
||||
|
||||
void InterpolatePosition(const CarlaRecorderPosition &Start, const CarlaRecorderPosition &End, double Per);
|
||||
|
||||
};
|
|
@ -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,6 +119,7 @@ void ATheNewCarlaGameModeBase::Tick(float DeltaSeconds)
|
|||
Super::Tick(DeltaSeconds);
|
||||
|
||||
GameInstance->Tick(DeltaSeconds);
|
||||
if (Recorder) Recorder->Tick(DeltaSeconds);
|
||||
}
|
||||
|
||||
void ATheNewCarlaGameModeBase::EndPlay(const EEndPlayReason::Type EndPlayReason)
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include "Carla/Actor/CarlaActorFactory.h"
|
||||
#include "Carla/Game/CarlaEpisode.h"
|
||||
#include "Carla/Game/CarlaGameInstance.h"
|
||||
#include "Carla/Game/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;
|
||||
|
|
|
@ -14,9 +14,6 @@
|
|||
|
||||
#include <compiler/disable-ue4-macros.h>
|
||||
#include <carla/sensor/SensorRegistry.h>
|
||||
#include <carla/recorder/Recorder.h>
|
||||
#include <carla/recorder/RecorderPosition.h>
|
||||
#include <carla/recorder/RecorderState.h>
|
||||
#include <carla/sensor/data/ActorDynamicState.h>
|
||||
#include <compiler/enable-ue4-macros.h>
|
||||
|
||||
|
@ -153,51 +150,4 @@ void AWorldObserver::Tick(float DeltaSeconds)
|
|||
);
|
||||
|
||||
AsyncStream.Send(*this, std::move(buffer));
|
||||
|
||||
// check if recording
|
||||
if (Episode->GetRecorder().isEnabled()) {
|
||||
const FActorRegistry ® = Episode->GetActorRegistry();
|
||||
|
||||
// get positions
|
||||
for (TActorIterator<ACarlaWheeledVehicle> It(GetWorld()); It; ++It)
|
||||
{
|
||||
ACarlaWheeledVehicle *Actor = *It;
|
||||
check(Actor != nullptr);
|
||||
carla::recorder::RecorderPosition recPos {
|
||||
reg.Find(Actor).GetActorId(),
|
||||
Actor->GetActorTransform()
|
||||
};
|
||||
Episode->GetRecorder().addPosition(std::move(recPos));
|
||||
}
|
||||
|
||||
// get states
|
||||
for (TActorIterator<ATrafficSignBase> It(GetWorld()); It; ++It)
|
||||
{
|
||||
ATrafficSignBase *Actor = *It;
|
||||
check(Actor != nullptr);
|
||||
auto TrafficLight = Cast<ATrafficLightBase>(Actor);
|
||||
if (TrafficLight != nullptr)
|
||||
{
|
||||
carla::recorder::RecorderStateTrafficLight recTraffic {
|
||||
reg.Find(Actor).GetActorId(),
|
||||
TrafficLight->GetTimeIsFrozen(),
|
||||
TrafficLight->GetElapsedTime(),
|
||||
static_cast<char>(TrafficLight->GetTrafficLightState())
|
||||
};
|
||||
Episode->GetRecorder().addState(std::move(recTraffic));
|
||||
}
|
||||
|
||||
// FActorDescription Description;
|
||||
// Description.Id = UCarlaEpisode_GetTrafficSignId(Actor->GetTrafficSignState());
|
||||
// Description.Class = Actor->GetClass();
|
||||
// ActorDispatcher->RegisterActor(*Actor, Description);
|
||||
}
|
||||
|
||||
// write
|
||||
Episode->GetRecorder().write();
|
||||
}
|
||||
|
||||
// replayer
|
||||
if (Episode->GetReplayer().isEnabled())
|
||||
Episode->GetReplayer().tick(DeltaSeconds);
|
||||
}
|
||||
|
|
|
@ -556,20 +556,20 @@ void FTheNewCarlaServer::FPimpl::BindActions()
|
|||
|
||||
Server.BindSync("stop_recorder", [this]() -> R<void> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
Episode->GetRecorder().stop();
|
||||
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(
|
||||
return R<std::string>(Episode->GetRecorder()->ShowFileInfo(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name));
|
||||
});
|
||||
|
||||
Server.BindSync("replay_file", [this](std::string name, double start, double duration) -> R<std::string> {
|
||||
REQUIRE_CARLA_EPISODE();
|
||||
return R<std::string>(Episode->GetRecorder().replayFile(
|
||||
return R<std::string>(Episode->GetRecorder()->ReplayFile(
|
||||
carla::rpc::FromFString(FPaths::ConvertRelativePathToFull(FPaths::ProjectSavedDir())),
|
||||
name,
|
||||
start,
|
||||
|
|
Loading…
Reference in New Issue