Add time to SensorData

This commit is contained in:
Pasch, Frederik 2019-03-06 15:22:39 +01:00
parent 84b801c4f3
commit 3d2e08611e
21 changed files with 76 additions and 32 deletions

View File

@ -1,4 +1,5 @@
## Latest Changes
* Add timestamp to SensorData
* Allow usage of hostname for carla::Client and resolve them to IP address
* Added `map.transform_to_geolocation` to transform Location to GNSS GeoLocation
* Added `id` property to waypoints, uniquely identifying waypoints up to half centimetre precision

View File

@ -30,10 +30,13 @@ sensor.listen(lambda data: do_something(data))
```
Note that each sensor has a different set of attributes and produces different
type of data. However, the data produced by a sensor comes always tagged with a
**frame number** and a **transform**. The frame number is used to identify the
frame at which the measurement took place, the transform gives you the
transformation in world coordinates of the sensor at that same frame.
type of data. However, the data produced by a sensor comes always tagged with:
| Sensor data attribute | Type | Description |
| --------------------- | ------ | ----------- |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
Most sensor data objects, like images and lidar measurements, have a function
for saving the measurements to disk.
@ -81,7 +84,8 @@ objects.
| Sensor data attribute | Type | Description |
| --------------------- | ---- | ----------- |
| `frame_number` | int | Frame count when the measurement took place |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `width` | int | Image width in pixels |
| `height` | int | Image height in pixels |
@ -108,7 +112,8 @@ objects.
| Sensor data attribute | Type | Description |
| --------------------- | ---- | ----------- |
| `frame_number` | int | Frame count when the measurement took place |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `width` | int | Image width in pixels |
| `height` | int | Image height in pixels |
@ -146,7 +151,8 @@ objects.
| Sensor data attribute | Type | Description |
| --------------------- | ---- | ----------- |
| `frame_number` | int | Frame count when the measurement took place |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `width` | int | Image width in pixels |
| `height` | int | Image height in pixels |
@ -213,7 +219,8 @@ objects.
| Sensor data attribute | Type | Description |
| -------------------------- | ---------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `horizontal_angle` | float | Angle in XY plane of the lidar this frame (in degrees) |
| `channels` | int | Number of channels (lasers) of the lidar |
@ -251,7 +258,8 @@ object for each collision registered
| Sensor data attribute | Type | Description |
| ---------------------- | ----------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `actor` | carla.Actor | Actor that measured the collision ("self" actor) |
| `other_actor` | carla.Actor | Actor against whom we collide |
@ -282,7 +290,8 @@ object for each lane marking crossed by the actor
| Sensor data attribute | Type | Description |
| ----------------------- | ----------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `actor` | carla.Actor | Actor that invaded another lane ("self" actor) |
| `crossed_lane_markings` | carla.LaneMarking list | List of lane markings that have been crossed |
@ -300,7 +309,8 @@ objects.
| Sensor data attribute | Type | Description |
| ---------------------- | ----------- | ----------- |
| `frame_number` | int | Frame count when the measurement took place |
| `frame_number` | int | Frame number when the measurement took place |
| `timestamp` | double | Timestamp of the measurement in simulation seconds since the beginning of the epispode |
| `transform` | carla.Transform | Transform in world coordinates of the sensor at the time of the measurement |
| `latitude` | double | Latitude position of the actor |
| `longitude` | double | Longitude position of the actor |

View File

@ -159,6 +159,7 @@
## `carla.SensorData`
- `frame_number`
- `timestamp`
- `transform`
## `carla.Image(carla.SensorData)`

View File

@ -55,6 +55,7 @@ namespace client {
try {
return MakeShared<sensor::data::GnssEvent>(
timestamp.frame_count,
timestamp.elapsed_seconds,
GetTransform(),
_geo_reference.Transform(GetLocation()));
} catch (const std::exception &e) {

View File

@ -92,6 +92,7 @@ namespace client {
nullptr :
MakeShared<sensor::data::LaneInvasionEvent>(
timestamp.frame_count,
timestamp.elapsed_seconds,
_vehicle->GetTransform(),
_vehicle,
crossed_lanes);

View File

@ -37,6 +37,11 @@ namespace sensor {
return GetHeader().frame_number;
}
/// Timestamp when the data was generated.
double GetTimestamp() const {
return GetHeader().timestamp;
}
/// Sensor's transform when the data was generated.
const rpc::Transform &GetSensorTransform() const {
return GetHeader().sensor_transform;

View File

@ -23,12 +23,13 @@ namespace sensor {
private NonCopyable {
protected:
SensorData(size_t frame_number, const rpc::Transform &sensor_transform)
SensorData(size_t frame_number, double timestamp, const rpc::Transform &sensor_transform)
: _frame_number(frame_number),
_timestamp(timestamp),
_sensor_transform(sensor_transform) {}
explicit SensorData(const RawData &data)
: SensorData(data.GetFrameNumber(), data.GetSensorTransform()) {}
: SensorData(data.GetFrameNumber(), data.GetTimestamp(), data.GetSensorTransform()) {}
public:
@ -39,6 +40,11 @@ namespace sensor {
return _frame_number;
}
/// Time the data was generated.
double GetTimestamp() const {
return _timestamp;
}
/// Sensor's transform when the data was generated.
const rpc::Transform &GetSensorTransform() const {
return _sensor_transform;
@ -58,6 +64,8 @@ namespace sensor {
const size_t _frame_number;
const double _timestamp;
const rpc::Transform _sensor_transform;
};

View File

@ -18,9 +18,10 @@ namespace data {
explicit GnssEvent(
size_t frame_number,
double timestamp,
const rpc::Transform &sensor_transform,
const geom::GeoLocation &geo_location)
: SensorData(frame_number, sensor_transform),
: SensorData(frame_number, timestamp, sensor_transform),
_geo_location(geo_location) {}
const geom::GeoLocation &GetGeoLocation() const {

View File

@ -23,10 +23,11 @@ namespace data {
explicit LaneInvasionEvent(
size_t frame_number,
double timestamp,
const rpc::Transform &sensor_transform,
SharedPtr<client::Actor> self_actor,
std::vector<LaneMarking> crossed_lane_markings)
: SensorData(frame_number, sensor_transform),
: SensorData(frame_number, timestamp, sensor_transform),
_self_actor(std::move(self_actor)),
_crossed_lane_markings(std::move(crossed_lane_markings)) {}

View File

@ -13,7 +13,7 @@ namespace sensor {
namespace s11n {
static_assert(
SensorHeaderSerializer::header_offset == 2u * 8u + 6u * 4u,
SensorHeaderSerializer::header_offset == 3u * 8u + 6u * 4u,
"Header size missmatch");
static Buffer PopBufferFromPool() {
@ -24,10 +24,12 @@ namespace s11n {
Buffer SensorHeaderSerializer::Serialize(
const uint64_t index,
const uint64_t frame,
double timestamp,
const rpc::Transform transform) {
Header h;
h.sensor_type = index;
h.frame_number = frame;
h.timestamp = timestamp;
h.sensor_transform = transform;
auto buffer = PopBufferFromPool();
buffer.copy_from(reinterpret_cast<const unsigned char *>(&h), sizeof(h));

View File

@ -21,13 +21,14 @@ namespace s11n {
struct Header {
uint64_t sensor_type;
uint64_t frame_number;
double timestamp;
rpc::Transform sensor_transform;
};
#pragma pack(pop)
constexpr static auto header_offset = sizeof(Header);
static Buffer Serialize(uint64_t index, uint64_t frame, rpc::Transform transform);
static Buffer Serialize(uint64_t index, uint64_t frame, double timestamp, rpc::Transform transform);
static const Header &Deserialize(const Buffer &message) {
return *reinterpret_cast<const Header *>(message.data());

View File

@ -28,6 +28,7 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const Image &image) {
out << "Image(frame=" << image.GetFrameNumber()
<< ", timestamp=" << image.GetTimestamp()
<< ", size=" << image.GetWidth() << 'x' << image.GetHeight()
<< ')';
return out;
@ -35,6 +36,7 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const LidarMeasurement &meas) {
out << "LidarMeasurement(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", number_of_points=" << meas.size()
<< ')';
return out;
@ -42,6 +44,7 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const CollisionEvent &meas) {
out << "CollisionEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", other_actor=" << meas.GetOtherActor()
<< ')';
return out;
@ -49,18 +52,22 @@ namespace data {
std::ostream &operator<<(std::ostream &out, const ObstacleDetectionEvent &meas) {
out << "ObstacleDetectionEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", other_actor=" << meas.GetOtherActor()
<< ')';
return out;
}
std::ostream &operator<<(std::ostream &out, const LaneInvasionEvent &meas) {
out << "LaneInvasionEvent(frame=" << meas.GetFrameNumber() << ')';
out << "LaneInvasionEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ')';
return out;
}
std::ostream &operator<<(std::ostream &out, const GnssEvent &meas) {
out << "GnssEvent(frame=" << meas.GetFrameNumber()
<< ", timestamp=" << meas.GetTimestamp()
<< ", lat=" << meas.GetLatitude()
<< ", lon=" << meas.GetLongitude()
<< ", alt=" << meas.GetAltitude()
@ -156,6 +163,7 @@ void export_sensor_data() {
class_<cs::SensorData, boost::noncopyable, boost::shared_ptr<cs::SensorData>>("SensorData", no_init)
.add_property("frame_number", &cs::SensorData::GetFrameNumber)
.add_property("timestamp", &cs::SensorData::GetTimestamp)
.add_property("transform", CALL_RETURNING_COPY(cs::SensorData, GetSensorTransform))
;

View File

@ -63,7 +63,7 @@ private:
/// @pre This functions needs to be called in the game-thread.
template <typename SensorT>
explicit FAsyncDataStreamTmpl(const SensorT &InSensor, StreamType InStream);
explicit FAsyncDataStreamTmpl(const SensorT &InSensor, float Timepoint, StreamType InStream);
StreamType Stream;
@ -95,13 +95,15 @@ template <typename T>
template <typename SensorT>
inline FAsyncDataStreamTmpl<T>::FAsyncDataStreamTmpl(
const SensorT &Sensor,
float Timepoint,
StreamType InStream)
: Stream(std::move(InStream)),
Header([&Sensor]() {
Header([&Sensor, Timepoint]() {
check(IsInGameThread());
using Serializer = carla::sensor::s11n::SensorHeaderSerializer;
return Serializer::Serialize(
carla::sensor::SensorRegistry::template get<SensorT*>::index,
GFrameCounter,
Timepoint,
Sensor.GetActorTransform());
}()) {}

View File

@ -62,7 +62,7 @@ void ACollisionSensor::OnCollisionEvent(
{
constexpr float TO_METERS = 1e-2;
NormalImpulse *= TO_METERS;
GetDataStream(*this).Send(
GetDataStream(*this, Actor->GetWorld()->GetTimeSeconds()).Send(
*this,
Episode->SerializeActor(Episode->FindOrFakeActor(Actor)),
Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)),

View File

@ -37,10 +37,10 @@ public:
///
/// @pre This functions needs to be called in the game-thread.
template <typename SensorT>
auto MakeAsyncDataStream(const SensorT &Sensor)
auto MakeAsyncDataStream(const SensorT &Sensor, float Timestamp)
{
check(Stream.has_value());
return FAsyncDataStreamTmpl<T>{Sensor, *Stream};
return FAsyncDataStreamTmpl<T>{Sensor, Timestamp, *Stream};
}
/// Return the token that allows subscribing to this stream.

View File

@ -134,7 +134,7 @@ void AObstacleDetectionSensor::Tick(float DeltaSeconds)
if (isHitReturned)
{
OnObstacleDetectionEvent(this, HitOut.Actor.Get(), HitOut.Distance, HitOut);
OnObstacleDetectionEvent(this, HitOut.Actor.Get(), HitOut.Distance, HitOut, currentWorld->GetTimeSeconds());
}
}
@ -142,11 +142,12 @@ void AObstacleDetectionSensor::OnObstacleDetectionEvent(
AActor *Actor,
AActor *OtherActor,
float HitDistance,
const FHitResult &Hit)
const FHitResult &Hit,
float Timestamp)
{
if ((Episode != nullptr) && (Actor != nullptr) && (OtherActor != nullptr))
{
GetDataStream(*this).Send(*this,
GetDataStream(*this, Timestamp).Send(*this,
Episode->SerializeActor(Episode->FindOrFakeActor(Actor)),
Episode->SerializeActor(Episode->FindOrFakeActor(OtherActor)),
HitRadius);

View File

@ -38,7 +38,8 @@ private:
AActor *Actor,
AActor *OtherActor,
float Distance,
const FHitResult &Hit);
const FHitResult &Hit,
float Timestamp);
UPROPERTY()
const UCarlaEpisode *Episode = nullptr;

View File

@ -87,7 +87,7 @@ void FPixelReader::SendPixelsInRenderThread(TSensor &Sensor)
// First we create the message header (needs to be created in the
// game-thread).
auto AsyncStream = Sensor.GetDataStream(Sensor);
auto AsyncStream = Sensor.GetDataStream(Sensor, Sensor.GetWorld()->GetTimeSeconds());
// We need a shared ptr here because UE4 macros do not move the arguments -_-
auto StreamPtr = std::make_shared<decltype(AsyncStream)>(std::move(AsyncStream));

View File

@ -69,7 +69,7 @@ void ARayCastLidar::Tick(const float DeltaTime)
ReadPoints(DeltaTime);
auto DataStream = GetDataStream(*this);
auto DataStream = GetDataStream(*this, GetWorld()->GetTimeSeconds());
DataStream.Send(*this, LidarMeasurement, DataStream.PopBufferFromPool());
}

View File

@ -47,9 +47,9 @@ protected:
/// You need to provide a reference to self, this is necessary for template
/// deduction.
template <typename SensorT>
FAsyncDataStream GetDataStream(const SensorT &Self)
FAsyncDataStream GetDataStream(const SensorT &Self, float Timestamp)
{
return Stream.MakeAsyncDataStream(Self);
return Stream.MakeAsyncDataStream(Self, Timestamp);
}
private:

View File

@ -150,7 +150,7 @@ static carla::Buffer FWorldObserver_Serialize(
void FWorldObserver::BroadcastTick(const UCarlaEpisode &Episode, float DeltaSeconds)
{
auto AsyncStream = Stream.MakeAsyncDataStream(*this);
auto AsyncStream = Stream.MakeAsyncDataStream(*this, Episode.GetWorld()->GetTimeSeconds());
auto buffer = FWorldObserver_Serialize(
AsyncStream.PopBufferFromPool(),