From 3d2e08611e58a25780976a0caf65f3532d888845 Mon Sep 17 00:00:00 2001 From: "Pasch, Frederik" Date: Wed, 6 Mar 2019 15:22:39 +0100 Subject: [PATCH] Add time to SensorData --- CHANGELOG.md | 1 + Docs/cameras_and_sensors.md | 32 ++++++++++++------- Docs/python_api.md | 1 + LibCarla/source/carla/client/GnssSensor.cpp | 1 + LibCarla/source/carla/client/LaneDetector.cpp | 1 + LibCarla/source/carla/sensor/RawData.h | 5 +++ LibCarla/source/carla/sensor/SensorData.h | 12 +++++-- LibCarla/source/carla/sensor/data/GnssEvent.h | 3 +- .../carla/sensor/data/LaneInvasionEvent.h | 3 +- .../sensor/s11n/SensorHeaderSerializer.cpp | 4 ++- .../sensor/s11n/SensorHeaderSerializer.h | 3 +- PythonAPI/source/libcarla/SensorData.cpp | 10 +++++- .../Source/Carla/Sensor/AsyncDataStream.h | 6 ++-- .../Source/Carla/Sensor/CollisionSensor.cpp | 2 +- .../Carla/Source/Carla/Sensor/DataStream.h | 4 +-- .../Carla/Sensor/ObstacleDetectionSensor.cpp | 7 ++-- .../Carla/Sensor/ObstacleDetectionSensor.h | 3 +- .../Carla/Source/Carla/Sensor/PixelReader.h | 2 +- .../Source/Carla/Sensor/RayCastLidar.cpp | 2 +- .../Carla/Source/Carla/Sensor/Sensor.h | 4 +-- .../Source/Carla/Sensor/WorldObserver.cpp | 2 +- 21 files changed, 76 insertions(+), 32 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 6186fb4fc..65d2bc608 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -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 diff --git a/Docs/cameras_and_sensors.md b/Docs/cameras_and_sensors.md index db657c1de..50e3c0460 100644 --- a/Docs/cameras_and_sensors.md +++ b/Docs/cameras_and_sensors.md @@ -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 | diff --git a/Docs/python_api.md b/Docs/python_api.md index 2b28f7808..440bf9bd1 100644 --- a/Docs/python_api.md +++ b/Docs/python_api.md @@ -159,6 +159,7 @@ ## `carla.SensorData` - `frame_number` +- `timestamp` - `transform` ## `carla.Image(carla.SensorData)` diff --git a/LibCarla/source/carla/client/GnssSensor.cpp b/LibCarla/source/carla/client/GnssSensor.cpp index a8b6330c1..af49e8d9d 100644 --- a/LibCarla/source/carla/client/GnssSensor.cpp +++ b/LibCarla/source/carla/client/GnssSensor.cpp @@ -55,6 +55,7 @@ namespace client { try { return MakeShared( timestamp.frame_count, + timestamp.elapsed_seconds, GetTransform(), _geo_reference.Transform(GetLocation())); } catch (const std::exception &e) { diff --git a/LibCarla/source/carla/client/LaneDetector.cpp b/LibCarla/source/carla/client/LaneDetector.cpp index 0809b3d66..d0ce1d2b3 100644 --- a/LibCarla/source/carla/client/LaneDetector.cpp +++ b/LibCarla/source/carla/client/LaneDetector.cpp @@ -92,6 +92,7 @@ namespace client { nullptr : MakeShared( timestamp.frame_count, + timestamp.elapsed_seconds, _vehicle->GetTransform(), _vehicle, crossed_lanes); diff --git a/LibCarla/source/carla/sensor/RawData.h b/LibCarla/source/carla/sensor/RawData.h index a4f4c13d5..51af63ffb 100644 --- a/LibCarla/source/carla/sensor/RawData.h +++ b/LibCarla/source/carla/sensor/RawData.h @@ -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; diff --git a/LibCarla/source/carla/sensor/SensorData.h b/LibCarla/source/carla/sensor/SensorData.h index 19fabf565..d5378281e 100644 --- a/LibCarla/source/carla/sensor/SensorData.h +++ b/LibCarla/source/carla/sensor/SensorData.h @@ -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; }; diff --git a/LibCarla/source/carla/sensor/data/GnssEvent.h b/LibCarla/source/carla/sensor/data/GnssEvent.h index 1e75e8a80..631f2151b 100644 --- a/LibCarla/source/carla/sensor/data/GnssEvent.h +++ b/LibCarla/source/carla/sensor/data/GnssEvent.h @@ -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 { diff --git a/LibCarla/source/carla/sensor/data/LaneInvasionEvent.h b/LibCarla/source/carla/sensor/data/LaneInvasionEvent.h index bf10e642b..6bee186a0 100644 --- a/LibCarla/source/carla/sensor/data/LaneInvasionEvent.h +++ b/LibCarla/source/carla/sensor/data/LaneInvasionEvent.h @@ -23,10 +23,11 @@ namespace data { explicit LaneInvasionEvent( size_t frame_number, + double timestamp, const rpc::Transform &sensor_transform, SharedPtr self_actor, std::vector 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)) {} diff --git a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp index dd79a9399..e6cce206b 100644 --- a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.cpp @@ -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(&h), sizeof(h)); diff --git a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h index 8e4831349..1a2b4acb5 100644 --- a/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/SensorHeaderSerializer.h @@ -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(message.data()); diff --git a/PythonAPI/source/libcarla/SensorData.cpp b/PythonAPI/source/libcarla/SensorData.cpp index 2d1d94b7d..716b9320b 100644 --- a/PythonAPI/source/libcarla/SensorData.cpp +++ b/PythonAPI/source/libcarla/SensorData.cpp @@ -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_>("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)) ; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStream.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStream.h index 6bdd8c113..9bfbd5033 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStream.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/AsyncDataStream.h @@ -63,7 +63,7 @@ private: /// @pre This functions needs to be called in the game-thread. template - explicit FAsyncDataStreamTmpl(const SensorT &InSensor, StreamType InStream); + explicit FAsyncDataStreamTmpl(const SensorT &InSensor, float Timepoint, StreamType InStream); StreamType Stream; @@ -95,13 +95,15 @@ template template inline FAsyncDataStreamTmpl::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::index, GFrameCounter, + Timepoint, Sensor.GetActorTransform()); }()) {} diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp index 15504622d..0ad68670f 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/CollisionSensor.cpp @@ -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)), diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DataStream.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DataStream.h index 1b945c72c..04106edb3 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DataStream.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/DataStream.h @@ -37,10 +37,10 @@ public: /// /// @pre This functions needs to be called in the game-thread. template - auto MakeAsyncDataStream(const SensorT &Sensor) + auto MakeAsyncDataStream(const SensorT &Sensor, float Timestamp) { check(Stream.has_value()); - return FAsyncDataStreamTmpl{Sensor, *Stream}; + return FAsyncDataStreamTmpl{Sensor, Timestamp, *Stream}; } /// Return the token that allows subscribing to this stream. diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp index d35db568b..aa23168a6 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.cpp @@ -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); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.h index 75c553e08..fea186d22 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/ObstacleDetectionSensor.h @@ -38,7 +38,8 @@ private: AActor *Actor, AActor *OtherActor, float Distance, - const FHitResult &Hit); + const FHitResult &Hit, + float Timestamp); UPROPERTY() const UCarlaEpisode *Episode = nullptr; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h index 8cf045d2c..c72f55f01 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/PixelReader.h @@ -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(std::move(AsyncStream)); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp index 3219f9784..e7f4c1517 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp @@ -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()); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h index 021e098f3..cb7e24b26 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/Sensor.h @@ -47,9 +47,9 @@ protected: /// You need to provide a reference to self, this is necessary for template /// deduction. template - FAsyncDataStream GetDataStream(const SensorT &Self) + FAsyncDataStream GetDataStream(const SensorT &Self, float Timestamp) { - return Stream.MakeAsyncDataStream(Self); + return Stream.MakeAsyncDataStream(Self, Timestamp); } private: diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp index 31803e64c..0b8c9ff37 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/WorldObserver.cpp @@ -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(),