90 it->second(actor, control);
101 const double fractional = modf(timestamp, &integral);
102 const double multiplier = 1000000000.0;
103 _seconds =
static_cast<int32_t
>(integral);
104 _nanoseconds =
static_cast<uint32_t
>(fractional * multiplier);
117 it->second.push_back(parent);
134 it->second = ros_name;
143 return std::string(
"");
152 std::string parent_name;
153 for (
auto parent_it = it->second.cbegin(); parent_it != it->second.cend(); ++parent_it)
156 if (name == current_actor_name)
164 parent_name = name +
'/' + parent_name;
166 if (parent_name.back() ==
'/')
167 parent_name.pop_back();
171 return std::string(
"");
178 _controller = std::make_shared<CarlaEgoVehicleControlSubscriber>(actor, ros_name.c_str());
190 std::shared_ptr<CarlaPublisher> publisher {};
191 std::shared_ptr<CarlaTransformPublisher> transform {};
193 publisher = it_publishers->second;
195 transform = it_transforms->second;
199 const std::string string_id = std::to_string(
id);
204 if (ros_name ==
"collision__") {
207 ros_name += string_id;
210 std::shared_ptr<CarlaCollisionPublisher> new_publisher = std::make_shared<CarlaCollisionPublisher>(ros_name.c_str(), parent_ros_name.c_str());
211 if (new_publisher->Init()) {
213 publisher = new_publisher;
215 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
216 if (new_transform->Init()) {
218 transform = new_transform;
222 if (ros_name ==
"depth__") {
225 ros_name += string_id;
228 std::shared_ptr<CarlaDepthCameraPublisher> new_publisher = std::make_shared<CarlaDepthCameraPublisher>(ros_name.c_str(), parent_ros_name.c_str());
229 if (new_publisher->Init()) {
231 publisher = new_publisher;
233 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
234 if (new_transform->Init()) {
236 transform = new_transform;
240 if (ros_name ==
"normals__") {
243 ros_name += string_id;
246 std::shared_ptr<CarlaNormalsCameraPublisher> new_publisher = std::make_shared<CarlaNormalsCameraPublisher>(ros_name.c_str(), parent_ros_name.c_str());
247 if (new_publisher->Init()) {
249 publisher = new_publisher;
251 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
252 if (new_transform->Init()) {
254 transform = new_transform;
258 if (ros_name ==
"dvs__") {
261 ros_name += string_id;
264 std::shared_ptr<CarlaDVSCameraPublisher> new_publisher = std::make_shared<CarlaDVSCameraPublisher>(ros_name.c_str(), parent_ros_name.c_str());
265 if (new_publisher->Init()) {
267 publisher = new_publisher;
269 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
270 if (new_transform->Init()) {
272 transform = new_transform;
276 if (ros_name ==
"gnss__") {
279 ros_name += string_id;
282 std::shared_ptr<CarlaGNSSPublisher> new_publisher = std::make_shared<CarlaGNSSPublisher>(ros_name.c_str(), parent_ros_name.c_str());
283 if (new_publisher->Init()) {
285 publisher = new_publisher;
287 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
288 if (new_transform->Init()) {
290 transform = new_transform;
294 if (ros_name ==
"imu__") {
297 ros_name += string_id;
300 std::shared_ptr<CarlaIMUPublisher> new_publisher = std::make_shared<CarlaIMUPublisher>(ros_name.c_str(), parent_ros_name.c_str());
301 if (new_publisher->Init()) {
303 publisher = new_publisher;
305 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
306 if (new_transform->Init()) {
308 transform = new_transform;
312 if (ros_name ==
"lane_invasion__") {
315 ros_name += string_id;
318 std::shared_ptr<CarlaLineInvasionPublisher> new_publisher = std::make_shared<CarlaLineInvasionPublisher>(ros_name.c_str(), parent_ros_name.c_str());
319 if (new_publisher->Init()) {
321 publisher = new_publisher;
323 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
324 if (new_transform->Init()) {
326 transform = new_transform;
330 std::cerr <<
"Obstacle detection sensor does not have an available publisher" << std::endl;
333 if (ros_name ==
"optical_flow__") {
336 ros_name += string_id;
339 std::shared_ptr<CarlaOpticalFlowCameraPublisher> new_publisher = std::make_shared<CarlaOpticalFlowCameraPublisher>(ros_name.c_str(), parent_ros_name.c_str());
340 if (new_publisher->Init()) {
342 publisher = new_publisher;
344 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
345 if (new_transform->Init()) {
347 transform = new_transform;
351 if (ros_name ==
"radar__") {
354 ros_name += string_id;
357 std::shared_ptr<CarlaRadarPublisher> new_publisher = std::make_shared<CarlaRadarPublisher>(ros_name.c_str(), parent_ros_name.c_str());
358 if (new_publisher->Init()) {
360 publisher = new_publisher;
362 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
363 if (new_transform->Init()) {
365 transform = new_transform;
369 if (ros_name ==
"ray_cast_semantic__") {
372 ros_name += string_id;
375 std::shared_ptr<CarlaSemanticLidarPublisher> new_publisher = std::make_shared<CarlaSemanticLidarPublisher>(ros_name.c_str(), parent_ros_name.c_str());
376 if (new_publisher->Init()) {
378 publisher = new_publisher;
380 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
381 if (new_transform->Init()) {
383 transform = new_transform;
387 if (ros_name ==
"ray_cast__") {
390 ros_name += string_id;
393 std::shared_ptr<CarlaLidarPublisher> new_publisher = std::make_shared<CarlaLidarPublisher>(ros_name.c_str(), parent_ros_name.c_str());
394 if (new_publisher->Init()) {
396 publisher = new_publisher;
398 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
399 if (new_transform->Init()) {
401 transform = new_transform;
405 std::cerr <<
"RSS sensor does not have an available publisher" << std::endl;
408 if (ros_name ==
"rgb__") {
411 ros_name += string_id;
414 std::shared_ptr<CarlaRGBCameraPublisher> new_publisher = std::make_shared<CarlaRGBCameraPublisher>(ros_name.c_str(), parent_ros_name.c_str());
415 if (new_publisher->Init()) {
417 publisher = new_publisher;
419 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
420 if (new_transform->Init()) {
422 transform = new_transform;
426 if (ros_name ==
"semantic_segmentation__") {
429 ros_name += string_id;
432 std::shared_ptr<CarlaSSCameraPublisher> new_publisher = std::make_shared<CarlaSSCameraPublisher>(ros_name.c_str(), parent_ros_name.c_str());
433 if (new_publisher->Init()) {
435 publisher = new_publisher;
437 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
438 if (new_transform->Init()) {
440 transform = new_transform;
444 if (ros_name ==
"instance_segmentation__") {
447 ros_name += string_id;
450 std::shared_ptr<CarlaISCameraPublisher> new_publisher = std::make_shared<CarlaISCameraPublisher>(ros_name.c_str(), parent_ros_name.c_str());
451 if (new_publisher->Init()) {
453 publisher = new_publisher;
455 std::shared_ptr<CarlaTransformPublisher> new_transform = std::make_shared<CarlaTransformPublisher>(ros_name.c_str(), parent_ros_name.c_str());
456 if (new_transform->Init()) {
458 transform = new_transform;
462 std::cerr <<
"World obserser does not have an available publisher" << std::endl;
465 std::cerr <<
"Camera GBuffer uint8 does not have an available publisher" << std::endl;
468 std::cerr <<
"Camera GBuffer float does not have an available publisher" << std::endl;
471 std::cerr <<
"Unknown sensor type" << std::endl;
475 return { publisher, transform };
479 uint64_t sensor_type,
482 int W,
int H,
float Fov,
486 switch (sensor_type) {
488 log_info(
"Sensor Collision to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
492 log_info(
"Sensor DepthCamera to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
495 std::shared_ptr<CarlaDepthCameraPublisher> publisher = std::dynamic_pointer_cast<
CarlaDepthCameraPublisher>(sensors.first);
500 if (!publisher->HasBeenInitialized())
501 publisher->InitInfoData(0, 0, H, W, Fov,
true);
504 publisher->Publish();
506 if (sensors.second) {
507 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
509 publisher->Publish();
514 log_info(
"Sensor NormalsCamera to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
523 if (!publisher->HasBeenInitialized())
524 publisher->InitInfoData(0, 0, H, W, Fov,
true);
527 publisher->Publish();
529 if (sensors.second) {
530 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
532 publisher->Publish();
537 log_info(
"Sensor LaneInvasionSensor to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
543 publisher->Publish();
545 if (sensors.second) {
546 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
548 publisher->Publish();
553 log_info(
"Sensor OpticalFlowCamera to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
562 if (!publisher->HasBeenInitialized())
563 publisher->InitInfoData(0, 0, H, W, Fov,
true);
566 publisher->Publish();
568 if (sensors.second) {
569 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
571 publisher->Publish();
576 log_info(
"Sensor RssSensor to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
580 log_info(
"Sensor SceneCaptureCamera to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
584 std::shared_ptr<CarlaRGBCameraPublisher> publisher = std::dynamic_pointer_cast<
CarlaRGBCameraPublisher>(sensors.first);
589 if (!publisher->HasBeenInitialized())
590 publisher->InitInfoData(0, 0, H, W, Fov,
true);
593 publisher->Publish();
595 if (sensors.second) {
596 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
598 publisher->Publish();
604 log_info(
"Sensor SemanticSegmentationCamera to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
608 std::shared_ptr<CarlaSSCameraPublisher> publisher = std::dynamic_pointer_cast<
CarlaSSCameraPublisher>(sensors.first);
613 if (!publisher->HasBeenInitialized())
614 publisher->InitInfoData(0, 0, H, W, Fov,
true);
617 publisher->Publish();
619 if (sensors.second) {
620 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
622 publisher->Publish();
627 log_info(
"Sensor InstanceSegmentationCamera to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
631 std::shared_ptr<CarlaISCameraPublisher> publisher = std::dynamic_pointer_cast<
CarlaISCameraPublisher>(sensors.first);
636 if (!publisher->HasBeenInitialized())
637 publisher->InitInfoData(0, 0, H, W, Fov,
true);
640 publisher->Publish();
642 if (sensors.second) {
643 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
645 publisher->Publish();
650 log_info(
"Sensor WorldObserver to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
653 log_info(
"Sensor CameraGBufferUint8 to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
656 log_info(
"Sensor CameraGBufferFloat to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
659 log_info(
"Sensor to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"buffer.", buffer->size());
664 uint64_t sensor_type,
672 std::shared_ptr<CarlaGNSSPublisher> publisher = std::dynamic_pointer_cast<
CarlaGNSSPublisher>(sensors.first);
674 publisher->Publish();
676 if (sensors.second) {
677 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
679 publisher->Publish();
684 uint64_t sensor_type,
691 log_info(
"Sensor InertialMeasurementUnit to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"imu.", accelerometer.
x, gyroscope.
x, compass);
694 std::shared_ptr<CarlaIMUPublisher> publisher = std::dynamic_pointer_cast<
CarlaIMUPublisher>(sensors.first);
695 publisher->
SetData(
_seconds,
_nanoseconds, reinterpret_cast<float*>(&accelerometer), reinterpret_cast<float*>(&gyroscope), compass);
696 publisher->Publish();
698 if (sensors.second) {
699 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
701 publisher->Publish();
706 uint64_t sensor_type,
710 int W,
int H,
float Fov,
712 log_info(
"Sensor DVS to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id);
715 std::shared_ptr<CarlaDVSCameraPublisher> publisher = std::dynamic_pointer_cast<
CarlaDVSCameraPublisher>(sensors.first);
720 if (!publisher->HasBeenInitialized())
721 publisher->InitInfoData(0, 0, H, W, Fov,
true);
726 publisher->Publish();
728 if (sensors.second) {
729 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
731 publisher->Publish();
736 uint64_t sensor_type,
741 log_info(
"Sensor Lidar to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"points.", data.
_points.size());
744 std::shared_ptr<CarlaLidarPublisher> publisher = std::dynamic_pointer_cast<
CarlaLidarPublisher>(sensors.first);
745 size_t width = data.
_points.size();
748 publisher->Publish();
750 if (sensors.second) {
751 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
753 publisher->Publish();
758 uint64_t sensor_type,
763 static_assert(
sizeof(
float) ==
sizeof(uint32_t),
"Invalid float size");
764 log_info(
"Sensor SemanticLidar to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"points.", data.
_ser_points.size());
771 publisher->Publish();
773 if (sensors.second) {
774 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
776 publisher->Publish();
781 uint64_t sensor_type,
786 log_info(
"Sensor Radar to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"points.", data.
_detections.size());
789 std::shared_ptr<CarlaRadarPublisher> publisher = std::dynamic_pointer_cast<
CarlaRadarPublisher>(sensors.first);
794 publisher->Publish();
796 if (sensors.second) {
797 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
799 publisher->Publish();
804 uint64_t sensor_type,
811 log_info(
"Sensor ObstacleDetector to ROS data: frame.",
_frame,
"sensor.", sensor_type,
"stream.", stream_id,
"distance.", distance);
815 uint64_t sensor_type,
818 uint32_t other_actor,
823 std::shared_ptr<CarlaCollisionPublisher> publisher = std::dynamic_pointer_cast<
CarlaCollisionPublisher>(sensors.first);
825 publisher->Publish();
827 if (sensors.second) {
828 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<
CarlaTransformPublisher>(sensors.second);
830 publisher->Publish();
836 element.second.reset();
839 element.second.reset();
std::string GetActorParentRosName(void *actor)
void SetData(int32_t seconds, uint32_t nanoseconds, float *accelerometer, float *gyroscope, float compass)
std::unordered_map< void *, std::string > _actor_ros_name
void ProcessDataFromIMU(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, carla::geom::Vector3D accelerometer, carla::geom::Vector3D gyroscope, float compass, void *actor=nullptr)
void RemoveActorRosName(void *actor)
std::unordered_map< void *, std::shared_ptr< CarlaPublisher > > _publishers
void SetFrame(uint64_t frame)
size_t GetDetectionCount() const
Returns the number of current detections.
void ProcessDataFromSemanticLidar(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, carla::sensor::data::SemanticLidarData &data, void *actor=nullptr)
This file contains definitions of common data structures used in traffic manager. ...
std::vector< SemanticLidarDetection > _ser_points
void SetData(int32_t seconds, uint32_t nanoseconds, const int32_t *data)
std::unordered_map< void *, std::vector< void * > > _actor_parent_ros_name
std::shared_ptr< CarlaEgoVehicleControlSubscriber > _controller
std::shared_ptr< CarlaClockPublisher > _clock_publisher
void ProcessDataFromDVS(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, const carla::SharedBufferView buffer, int W, int H, float Fov, void *actor=nullptr)
std::vector< RadarDetection > _detections
static constexpr auto header_offset
carla::streaming::detail::stream_id_type stream_id
std::pair< std::shared_ptr< CarlaPublisher >, std::shared_ptr< CarlaTransformPublisher > > GetOrCreateSensor(int type, carla::streaming::detail::stream_id_type id, void *actor)
void RemoveActorCallback(void *actor)
void AddActorParentRosName(void *actor, void *parent)
static void log_info(Args &&... args)
void ProcessDataFromRadar(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, const carla::sensor::data::RadarData &data, void *actor=nullptr)
void UpdateActorRosName(void *actor, std::string ros_name)
void ProcessDataFromCamera(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, int W, int H, float Fov, const carla::SharedBufferView buffer, void *actor=nullptr)
void ProcessDataFromCollisionSensor(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, uint32_t other_actor, carla::geom::Vector3D impulse, void *actor)
void ProcessDataFromObstacleDetection(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, AActor *first_actor, AActor *second_actor, float distance, void *actor=nullptr)
static constexpr auto header_offset
std::function< void(void *actor, ROS2CallbackData data)> ActorCallback
void AddActorRosName(void *actor, std::string ros_name)
std::string GetActorRosName(void *actor)
std::unordered_map< void *, std::shared_ptr< CarlaTransformPublisher > > _transforms
std::shared_ptr< BufferView > SharedBufferView
void SetTimestamp(double timestamp)
void ProcessDataFromGNSS(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, const carla::geom::GeoLocation &data, void *actor=nullptr)
void SetData(int32_t seconds, uint32_t nanoseconds, uint32_t actor_id, float x, float y, float z)
std::unordered_map< void *, ActorCallback > _actor_callbacks
void ProcessDataFromLidar(uint64_t sensor_type, carla::streaming::detail::stream_id_type stream_id, const carla::geom::Transform sensor_transform, carla::sensor::data::LidarData &data, void *actor=nullptr)
static std::shared_ptr< ROS2 > _instance
void SetData(int32_t seconds, uint32_t nanoseconds, const double *data)
void AddActorCallback(void *actor, std::string ros_name, ActorCallback callback)
std::vector< float > _points