diff --git a/LibCarla/source/carla/sensor/SensorRegistry.h b/LibCarla/source/carla/sensor/SensorRegistry.h index 6958acd06..fadee6f3d 100644 --- a/LibCarla/source/carla/sensor/SensorRegistry.h +++ b/LibCarla/source/carla/sensor/SensorRegistry.h @@ -20,11 +20,11 @@ #include "carla/sensor/s11n/GnssSerializer.h" #include "carla/sensor/s11n/ImageSerializer.h" #include "carla/sensor/s11n/IMUSerializer.h" -#include "carla/sensor/s11n/LidarRawSerializer.h" #include "carla/sensor/s11n/LidarSerializer.h" #include "carla/sensor/s11n/NoopSerializer.h" #include "carla/sensor/s11n/ObstacleDetectionEventSerializer.h" #include "carla/sensor/s11n/RadarSerializer.h" +#include "carla/sensor/s11n/SemanticLidarSerializer.h" // 2. Add a forward-declaration of the sensor here. class ACollisionSensor; @@ -61,7 +61,7 @@ namespace sensor { std::pair, std::pair, std::pair, - std::pair, + std::pair, std::pair, std::pair, std::pair, diff --git a/LibCarla/source/carla/sensor/data/LidarData.h b/LibCarla/source/carla/sensor/data/LidarData.h index 7a684c49c..73d325047 100644 --- a/LibCarla/source/carla/sensor/data/LidarData.h +++ b/LibCarla/source/carla/sensor/data/LidarData.h @@ -7,7 +7,7 @@ #pragma once #include "carla/rpc/Location.h" -#include "carla/sensor/data/LidarRawData.h" +#include "carla/sensor/data/SemanticLidarData.h" #include #include @@ -68,11 +68,11 @@ namespace data { } }; - class LidarData : public LidarRawData{ + class LidarData : public SemanticLidarData{ public: explicit LidarData(uint32_t ChannelCount = 0u) - : LidarRawData(ChannelCount) { + : SemanticLidarData(ChannelCount) { } LidarData &operator=(LidarData &&) = default; @@ -100,7 +100,7 @@ namespace data { _points.emplace_back(detection.intensity); } - virtual void WritePointSync(LidarRawDetection &detection) { + virtual void WritePointSync(SemanticLidarDetection &detection) { (void) detection; DEBUG_ASSERT(false); } diff --git a/LibCarla/source/carla/sensor/data/LidarRawData.h b/LibCarla/source/carla/sensor/data/SemanticLidarData.h similarity index 82% rename from LibCarla/source/carla/sensor/data/LidarRawData.h rename to LibCarla/source/carla/sensor/data/SemanticLidarData.h index fcb43268a..30d711d05 100644 --- a/LibCarla/source/carla/sensor/data/LidarRawData.h +++ b/LibCarla/source/carla/sensor/data/SemanticLidarData.h @@ -16,8 +16,8 @@ namespace carla { namespace sensor { namespace s11n { - class LidarRawSerializer; - class LidarRawHeaderView; + class SemanticLidarSerializer; + class SemanticLidarHeaderView; } namespace data { @@ -48,18 +48,18 @@ namespace data { /// #pragma pack(push, 1) - class LidarRawDetection { + class SemanticLidarDetection { public: geom::Location point{}; float cos_inc_angle{}; uint32_t object_idx{}; uint32_t object_tag{}; - LidarRawDetection() = default; + SemanticLidarDetection() = default; - LidarRawDetection(float x, float y, float z, float cosTh, uint32_t idx, uint32_t tag) : + SemanticLidarDetection(float x, float y, float z, float cosTh, uint32_t idx, uint32_t tag) : point(x, y, z), cos_inc_angle{cosTh}, object_idx{idx}, object_tag{tag} { } - LidarRawDetection(geom::Location p, float cosTh, uint32_t idx, uint32_t tag) : + SemanticLidarDetection(geom::Location p, float cosTh, uint32_t idx, uint32_t tag) : point(p), cos_inc_angle{cosTh}, object_idx{idx}, object_tag{tag} { } void WritePlyHeaderInfo(std::ostream& out) const{ @@ -78,7 +78,7 @@ namespace data { }; #pragma pack(pop) - class LidarRawData { + class SemanticLidarData { static_assert(sizeof(float) == sizeof(uint32_t), "Invalid float size"); protected: @@ -89,14 +89,14 @@ namespace data { }; public: - explicit LidarRawData(uint32_t ChannelCount = 0u) + explicit SemanticLidarData(uint32_t ChannelCount = 0u) : _header(Index::SIZE + ChannelCount, 0u) { _header[Index::ChannelCount] = ChannelCount; } - LidarRawData &operator=(LidarRawData &&) = default; + SemanticLidarData &operator=(SemanticLidarData &&) = default; - virtual ~LidarRawData() {} + virtual ~SemanticLidarData() {} float GetHorizontalAngle() const { return reinterpret_cast(_header[Index::HorizontalAngle]); @@ -124,7 +124,7 @@ namespace data { _ser_points.reserve(total_points); } - virtual void WritePointSync(LidarRawDetection &detection) { + virtual void WritePointSync(SemanticLidarDetection &detection) { _ser_points.emplace_back(detection); } @@ -133,10 +133,10 @@ namespace data { uint32_t _max_channel_points; private: - std::vector _ser_points; + std::vector _ser_points; - friend class s11n::LidarRawHeaderView; - friend class s11n::LidarRawSerializer; + friend class s11n::SemanticLidarHeaderView; + friend class s11n::SemanticLidarSerializer; }; } // namespace s11n diff --git a/LibCarla/source/carla/sensor/data/LidarRawMeasurement.h b/LibCarla/source/carla/sensor/data/SemanticLidarMeasurement.h similarity index 77% rename from LibCarla/source/carla/sensor/data/LidarRawMeasurement.h rename to LibCarla/source/carla/sensor/data/SemanticLidarMeasurement.h index 993b0c965..0c25e8e09 100644 --- a/LibCarla/source/carla/sensor/data/LidarRawMeasurement.h +++ b/LibCarla/source/carla/sensor/data/SemanticLidarMeasurement.h @@ -9,7 +9,7 @@ #include "carla/Debug.h" #include "carla/rpc/Location.h" #include "carla/sensor/data/Array.h" -#include "carla/sensor/s11n/LidarRawSerializer.h" +#include "carla/sensor/s11n/SemanticLidarSerializer.h" namespace carla { namespace sensor { @@ -17,16 +17,16 @@ namespace data { /// Measurement produced by a Lidar. Consists of an array of 3D points plus /// some extra meta-information about the Lidar. - class LidarRawMeasurement : public Array { - static_assert(sizeof(data::LidarRawDetection) == 6u * sizeof(float), "LidarRawDetection size missmatch"); - using Super = Array; + class SemanticLidarMeasurement : public Array { + static_assert(sizeof(data::SemanticLidarDetection) == 6u * sizeof(float), "SemanticLidarDetection size missmatch"); + using Super = Array; protected: - using Serializer = s11n::LidarRawSerializer; + using Serializer = s11n::SemanticLidarSerializer; friend Serializer; - explicit LidarRawMeasurement(RawData &&data) + explicit SemanticLidarMeasurement(RawData &&data) : Super(std::move(data), [](const RawData &d) { return Serializer::GetHeaderOffset(d); }) {} diff --git a/LibCarla/source/carla/sensor/s11n/LidarRawSerializer.cpp b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.cpp similarity index 53% rename from LibCarla/source/carla/sensor/s11n/LidarRawSerializer.cpp rename to LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.cpp index e787c1028..de06613a3 100644 --- a/LibCarla/source/carla/sensor/s11n/LidarRawSerializer.cpp +++ b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.cpp @@ -4,16 +4,16 @@ // This work is licensed under the terms of the MIT license. // For a copy, see . -#include "carla/sensor/s11n/LidarRawSerializer.h" -#include "carla/sensor/data/LidarRawMeasurement.h" +#include "carla/sensor/s11n/SemanticLidarSerializer.h" +#include "carla/sensor/data/SemanticLidarMeasurement.h" namespace carla { namespace sensor { namespace s11n { - SharedPtr LidarRawSerializer::Deserialize(RawData &&data) { - return SharedPtr( - new data::LidarRawMeasurement{std::move(data)}); + SharedPtr SemanticLidarSerializer::Deserialize(RawData &&data) { + return SharedPtr( + new data::SemanticLidarMeasurement{std::move(data)}); } } // namespace s11n diff --git a/LibCarla/source/carla/sensor/s11n/LidarRawSerializer.h b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h similarity index 76% rename from LibCarla/source/carla/sensor/s11n/LidarRawSerializer.h rename to LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h index f86016a51..b7120c53e 100644 --- a/LibCarla/source/carla/sensor/s11n/LidarRawSerializer.h +++ b/LibCarla/source/carla/sensor/s11n/SemanticLidarSerializer.h @@ -9,7 +9,7 @@ #include "carla/Debug.h" #include "carla/Memory.h" #include "carla/sensor/RawData.h" -#include "carla/sensor/data/LidarRawData.h" +#include "carla/sensor/data/SemanticLidarData.h" namespace carla { namespace sensor { @@ -19,12 +19,12 @@ class SensorData; namespace s11n { // =========================================================================== - // -- LidarRawHeaderView -------------------------------------------------------- + // -- SemanticLidarHeaderView -------------------------------------------------------- // =========================================================================== /// A view over the header of a Lidar measurement. - class LidarRawHeaderView { - using Index = data::LidarRawData::Index; + class SemanticLidarHeaderView { + using Index = data::SemanticLidarData::Index; public: @@ -42,9 +42,9 @@ namespace s11n { } protected: - friend class LidarRawSerializer; + friend class SemanticLidarSerializer; - explicit LidarRawHeaderView(const uint32_t *begin) : _begin(begin) { + explicit SemanticLidarHeaderView(const uint32_t *begin) : _begin(begin) { DEBUG_ASSERT(_begin != nullptr); } @@ -56,22 +56,22 @@ namespace s11n { // =========================================================================== /// Serializes the data generated by Lidar sensors. - class LidarRawSerializer { + class SemanticLidarSerializer { public: - static LidarRawHeaderView DeserializeHeader(const RawData &data) { - return LidarRawHeaderView{reinterpret_cast(data.begin())}; + static SemanticLidarHeaderView DeserializeHeader(const RawData &data) { + return SemanticLidarHeaderView{reinterpret_cast(data.begin())}; } static size_t GetHeaderOffset(const RawData &data) { auto View = DeserializeHeader(data); - return sizeof(uint32_t) * (View.GetChannelCount() + data::LidarRawData::Index::SIZE); + return sizeof(uint32_t) * (View.GetChannelCount() + data::SemanticLidarData::Index::SIZE); } template static Buffer Serialize( const Sensor &sensor, - const data::LidarRawData &measurement, + const data::SemanticLidarData &measurement, Buffer &&output); static SharedPtr Deserialize(RawData &&data); @@ -82,9 +82,9 @@ namespace s11n { // =========================================================================== template - inline Buffer LidarRawSerializer::Serialize( + inline Buffer SemanticLidarSerializer::Serialize( const Sensor &, - const data::LidarRawData &measurement, + const data::SemanticLidarData &measurement, Buffer &&output) { std::array seq = { boost::asio::buffer(measurement._header), diff --git a/PythonAPI/carla/source/libcarla/SensorData.cpp b/PythonAPI/carla/source/libcarla/SensorData.cpp index 62c49299c..58eaffd35 100644 --- a/PythonAPI/carla/source/libcarla/SensorData.cpp +++ b/PythonAPI/carla/source/libcarla/SensorData.cpp @@ -16,7 +16,7 @@ #include #include #include -#include +#include #include #include #include @@ -48,8 +48,8 @@ namespace data { return out; } - std::ostream &operator<<(std::ostream &out, const LidarRawMeasurement &meas) { - out << "LidarRawMeasurement(frame=" << std::to_string(meas.GetFrame()) + std::ostream &operator<<(std::ostream &out, const SemanticLidarMeasurement &meas) { + out << "SemanticLidarMeasurement(frame=" << std::to_string(meas.GetFrame()) << ", timestamp=" << std::to_string(meas.GetTimestamp()) << ", number_of_points=" << std::to_string(meas.size()) << ')'; @@ -143,8 +143,8 @@ namespace data { return out; } - std::ostream &operator<<(std::ostream &out, const LidarRawDetection &det) { - out << "LidarRawDetection(x=" << std::to_string(det.point.x) + std::ostream &operator<<(std::ostream &out, const SemanticLidarDetection &det) { + out << "SemanticLidarDetection(x=" << std::to_string(det.point.x) << ", y=" << std::to_string(det.point.y) << ", z=" << std::to_string(det.point.z) << ", cos_inc_angle=" << std::to_string(det.cos_inc_angle) @@ -289,18 +289,18 @@ void export_sensor_data() { .def(self_ns::str(self_ns::self)) ; - class_, boost::noncopyable, boost::shared_ptr>("LidarRawMeasurement", no_init) - .add_property("horizontal_angle", &csd::LidarRawMeasurement::GetHorizontalAngle) - .add_property("channels", &csd::LidarRawMeasurement::GetChannelCount) - .add_property("raw_data", &GetRawDataAsBuffer) - .def("get_point_count", &csd::LidarRawMeasurement::GetPointCount, (arg("channel"))) - .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) - .def("__len__", &csd::LidarRawMeasurement::size) - .def("__iter__", iterator()) - .def("__getitem__", +[](const csd::LidarRawMeasurement &self, size_t pos) -> csd::LidarRawDetection { + class_, boost::noncopyable, boost::shared_ptr>("SemanticLidarMeasurement", no_init) + .add_property("horizontal_angle", &csd::SemanticLidarMeasurement::GetHorizontalAngle) + .add_property("channels", &csd::SemanticLidarMeasurement::GetChannelCount) + .add_property("raw_data", &GetRawDataAsBuffer) + .def("get_point_count", &csd::SemanticLidarMeasurement::GetPointCount, (arg("channel"))) + .def("save_to_disk", &SavePointCloudToDisk, (arg("path"))) + .def("__len__", &csd::SemanticLidarMeasurement::size) + .def("__iter__", iterator()) + .def("__getitem__", +[](const csd::SemanticLidarMeasurement &self, size_t pos) -> csd::SemanticLidarDetection { return self.at(pos); }) - .def("__setitem__", +[](csd::LidarRawMeasurement &self, size_t pos, const csd::LidarRawDetection &detection) { + .def("__setitem__", +[](csd::SemanticLidarMeasurement &self, size_t pos, const csd::SemanticLidarDetection &detection) { self.at(pos) = detection; }) .def(self_ns::str(self_ns::self)) @@ -368,11 +368,11 @@ void export_sensor_data() { .def(self_ns::str(self_ns::self)) ; - class_("LidarRawDetection") - .def_readwrite("point", &csd::LidarRawDetection::point) - .def_readwrite("cos_inc_angle", &csd::LidarRawDetection::cos_inc_angle) - .def_readwrite("object_idx", &csd::LidarRawDetection::object_idx) - .def_readwrite("object_tag", &csd::LidarRawDetection::object_tag) + class_("SemanticLidarDetection") + .def_readwrite("point", &csd::SemanticLidarDetection::point) + .def_readwrite("cos_inc_angle", &csd::SemanticLidarDetection::cos_inc_angle) + .def_readwrite("object_idx", &csd::SemanticLidarDetection::object_idx) + .def_readwrite("object_tag", &csd::SemanticLidarDetection::object_tag) .def(self_ns::str(self_ns::self)) ; diff --git a/PythonAPI/examples/opend3d.py b/PythonAPI/examples/opend3d.py index 81d150b8e..6ca5a84c1 100644 --- a/PythonAPI/examples/opend3d.py +++ b/PythonAPI/examples/opend3d.py @@ -79,7 +79,7 @@ def lidar_callback(point_cloud, point_list): point_list.colors = o3d.utility.Vector3dVector(int_color) -def raw_lidar_callback(point_cloud, point_list): +def semantic_lidar_callback(point_cloud, point_list): """Prepares a point cloud with semantic segmentation colors ready to be consumed by Open3D""" data = np.frombuffer(point_cloud.raw_data, dtype=np.dtype([ @@ -107,8 +107,8 @@ def raw_lidar_callback(point_cloud, point_list): def generate_lidar_bp(arg, world, blueprint_library, delta): """Generates a CARLA blueprint based on the script parameters""" - if arg.raw: - lidar_bp = world.get_blueprint_library().find('sensor.lidar.ray_cast_raw') + if arg.semantic: + lidar_bp = world.get_blueprint_library().find('sensor.lidar.ray_cast_semantic') else: lidar_bp = blueprint_library.find('sensor.lidar.ray_cast') if arg.no_noise: @@ -179,8 +179,8 @@ def main(arg): lidar = world.spawn_actor(lidar_bp, lidar_transform, attach_to=vehicle) point_list = o3d.geometry.PointCloud() - if arg.raw: - lidar.listen(lambda data: raw_lidar_callback(data, point_list)) + if arg.semantic: + lidar.listen(lambda data: semantic_lidar_callback(data, point_list)) else: lidar.listen(lambda data: lidar_callback(data, point_list)) @@ -247,14 +247,14 @@ if __name__ == "__main__": ' performance but you will lose the articulated objects in the' ' lidar, such as pedestrians') argparser.add_argument( - '--raw', + '--semantic', action='store_true', - help='use the raw lidar instead, which provides ground truth' + help='use the semantic lidar instead, which provides ground truth' ' information') argparser.add_argument( '--no-noise', action='store_true', - help='remove the drop off and noise from the normal (non-raw) lidar') + help='remove the drop off and noise from the normal (non-semantic) lidar') argparser.add_argument( '--no-autopilot', action='store_false', @@ -292,7 +292,7 @@ if __name__ == "__main__": '--points-per-second', default=500000, type=int, - help='lidar\'s maximum range in meters (default: 500000)') + help='lidar\'s points per second (default: 500000)') argparser.add_argument( '-x', default=0.0, diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp index 4a956a357..776bf7ffd 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Actor/ActorBlueprintFunctionLibrary.cpp @@ -873,7 +873,7 @@ void UActorBlueprintFunctionLibrary::MakeLidarDefinition( AtmospAttenRate, DropOffGenRate, DropOffIntensityLimit, DropOffAtZeroIntensity, StdDevLidar}); } - else if (Id == "ray_cast_raw") { + else if (Id == "ray_cast_semantic") { Definition.Variations.Append( {Channels, Range, PointsPerSecond, Frequency, UpperFOV, LowerFOV}); } diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp index faae55551..7757e6bff 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.cpp @@ -64,7 +64,7 @@ void ARayCastLidar::Tick(const float DeltaTime) DataStream.Send(*this, LidarData, DataStream.PopBufferFromPool()); } -float ARayCastLidar::ComputeIntensity(const FRawDetection& RawDetection) const +float ARayCastLidar::ComputeIntensity(const FSemanticDetection& RawDetection) const { const carla::geom::Location HitPoint = RawDetection.point; const float Distance = HitPoint.Length(); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.h index 6585339f5..7273aec52 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastLidar.h @@ -37,7 +37,7 @@ public: private: /// Compute the received intensity of the point - float ComputeIntensity(const FRawDetection& RawDetection) const; + float ComputeIntensity(const FSemanticDetection& RawDetection) const; FDetection ComputeDetection(const FHitResult& HitInfo, const FTransform& SensorTransf) const; bool PreprocessRay() const override; diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp index 196f4d090..991576048 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.cpp @@ -1,4 +1,4 @@ -// Copyright (c) 2017 Computer Vision Center (CVC) at the Universitat Autonoma +// Copyright (c) 2020 Computer Vision Center (CVC) at the Universitat Autonoma // de Barcelona (UAB). // // This work is licensed under the terms of the MIT license. @@ -21,7 +21,7 @@ FActorDefinition ARayCastSemanticLidar::GetSensorDefinition() { - return UActorBlueprintFunctionLibrary::MakeLidarDefinition(TEXT("ray_cast_raw")); + return UActorBlueprintFunctionLibrary::MakeLidarDefinition(TEXT("ray_cast_semantic")); } ARayCastSemanticLidar::ARayCastSemanticLidar(const FObjectInitializer& ObjectInitializer) @@ -41,7 +41,7 @@ void ARayCastSemanticLidar::Set(const FActorDescription &ActorDescription) void ARayCastSemanticLidar::Set(const FLidarDescription &LidarDescription) { Description = LidarDescription; - LidarRawData = FLidarRawData(Description.Channels); + SemanticLidarData = FSemanticLidarData(Description.Channels); CreateLasers(); PointsPerChannel.resize(Description.Channels); } @@ -69,7 +69,7 @@ void ARayCastSemanticLidar::Tick(const float DeltaTime) SimulateLidar(DeltaTime); auto DataStream = GetDataStream(*this); - DataStream.Send(*this, LidarRawData, DataStream.PopBufferFromPool()); + DataStream.Send(*this, SemanticLidarData, DataStream.PopBufferFromPool()); } void ARayCastSemanticLidar::SimulateLidar(const float DeltaTime) @@ -92,7 +92,7 @@ void ARayCastSemanticLidar::SimulateLidar(const float DeltaTime) check(ChannelCount == LaserAngles.Num()); const float CurrentHorizontalAngle = carla::geom::Math::ToDegrees( - LidarRawData.GetHorizontalAngle()); + SemanticLidarData.GetHorizontalAngle()); const float AngleDistanceOfTick = Description.RotationFrequency * 360.0f * DeltaTime; const float AngleDistanceOfLaserMeasure = AngleDistanceOfTick / PointsToScanWithOneLaser; @@ -122,7 +122,7 @@ void ARayCastSemanticLidar::SimulateLidar(const float DeltaTime) const float HorizontalAngle = carla::geom::Math::ToRadians( std::fmod(CurrentHorizontalAngle + AngleDistanceOfTick, 360.0f)); - LidarRawData.SetHorizontalAngle(HorizontalAngle); + SemanticLidarData.SetHorizontalAngle(HorizontalAngle); } void ARayCastSemanticLidar::ResetRecordedHits(uint32_t Channels, uint32_t MaxPointsPerChannel) { @@ -141,18 +141,18 @@ void ARayCastSemanticLidar::SimulateLidar(const float DeltaTime) void ARayCastSemanticLidar::ComputeAndSaveDetections(const FTransform& SensorTransform) { for (auto idxChannel = 0u; idxChannel < Description.Channels; ++idxChannel) PointsPerChannel[idxChannel] = RecordedHits[idxChannel].size(); - LidarRawData.ResetSerPoints(PointsPerChannel); + SemanticLidarData.ResetSerPoints(PointsPerChannel); for (auto idxChannel = 0u; idxChannel < Description.Channels; ++idxChannel) { for (auto& hit : RecordedHits[idxChannel]) { - FRawDetection detection; + FSemanticDetection detection; ComputeRawDetection(hit, SensorTransform, detection); - LidarRawData.WritePointSync(detection); + SemanticLidarData.WritePointSync(detection); } } } -void ARayCastSemanticLidar::ComputeRawDetection(const FHitResult& HitInfo, const FTransform& SensorTransf, FRawDetection& Detection) const +void ARayCastSemanticLidar::ComputeRawDetection(const FHitResult& HitInfo, const FTransform& SensorTransf, FSemanticDetection& Detection) const { const FVector HitPoint = HitInfo.ImpactPoint; Detection.point = SensorTransf.Inverse().TransformPosition(HitPoint); diff --git a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.h b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.h index 436294f99..a2f640704 100644 --- a/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.h +++ b/Unreal/CarlaUE4/Plugins/Carla/Source/Carla/Sensor/RayCastSemanticLidar.h @@ -15,7 +15,7 @@ #include "Carla/Actor/ActorBlueprintFunctionLibrary.h" #include -#include +#include #include #include "RayCastSemanticLidar.generated.h" @@ -28,8 +28,8 @@ class CARLA_API ARayCastSemanticLidar : public ASensor protected: - using FLidarRawData = carla::sensor::data::LidarRawData; - using FRawDetection = carla::sensor::data::LidarRawDetection; + using FSemanticLidarData = carla::sensor::data::SemanticLidarData; + using FSemanticDetection = carla::sensor::data::SemanticLidarDetection; public: static FActorDefinition GetSensorDefinition(); @@ -49,7 +49,7 @@ protected: void SimulateLidar(float DeltaTime); /// Shoot a laser ray-trace, return whether the laser hit something. - bool ShootLaser(const float VerticalAngle, float HorizontalAngle, FHitResult &RawData) const; + bool ShootLaser(const float VerticalAngle, float HorizontalAngle, FHitResult &HitResult) const; /// Method that allow to preprocess the ray before shoot it virtual bool PreprocessRay() const { @@ -59,7 +59,7 @@ protected: } /// Compute all raw detection information - void ComputeRawDetection(const FHitResult &HitInfo, const FTransform &SensorTransf, FRawDetection &Detection) const; + void ComputeRawDetection(const FHitResult &HitInfo, const FTransform &SensorTransf, FSemanticDetection &Detection) const; /// Saving the hits the raycast returns per channel void WritePointAsync(uint32_t Channel, FHitResult &Detection); @@ -80,6 +80,6 @@ protected: std::vector PointsPerChannel; private: - FLidarRawData LidarRawData; + FSemanticLidarData SemanticLidarData; };