CARLA
 
载入中...
搜索中...
未找到
ROS2.cpp
浏览该文件的文档.
1// Copyright (c) 2023 Computer Vision Center (CVC) at the Universitat Autonoma
2// de Barcelona (UAB).
3//
4// This work is licensed under the terms of the MIT license.
5// For a copy, see <https://opensource.org/licenses/MIT>.
6
7#include "carla/Logging.h"
8#include "carla/ros2/ROS2.h"
10#include "carla/geom/Vector3D.h"
18
38
41
42#include <vector>
43
44namespace carla {
45namespace ros2 {
46
47// 静态字段
48std::shared_ptr<ROS2> ROS2::_instance;
49
50// 传感器列表(应该等同于SensorsRegistry列表)
72
73void ROS2::Enable(bool enable) {
74 _enabled = enable;
75 log_info("ROS2 enabled: ", _enabled);
76 _clock_publisher = std::make_shared<CarlaClockPublisher>("clock", "");
77 _clock_publisher->Init();
78}
79
80void ROS2::SetFrame(uint64_t frame) {
81 _frame = frame;
82 //log_info("ROS2 new frame: ", _frame);
83 if (_controller) {
84 void* actor = _controller->GetVehicle();
85 if (_controller->IsAlive()) {
86 if (_controller->HasNewMessage()) {
87 auto it = _actor_callbacks.find(actor);
88 if (it != _actor_callbacks.end()) {
89 VehicleControl control = _controller->GetMessage();
90 it->second(actor, control);
91 }
92 }
93 } else {
95 }
96 }
97}
98
99void ROS2::SetTimestamp(double timestamp) {
100 double integral;
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);
106 _clock_publisher->Publish();
107 //log_info("ROS2 new timestamp: ", _timestamp);
108}
109
110void ROS2::AddActorRosName(void *actor, std::string ros_name) {
111 _actor_ros_name.insert({actor, ros_name});
112}
113
114void ROS2::AddActorParentRosName(void *actor, void* parent) {
115 auto it = _actor_parent_ros_name.find(actor);
116 if (it != _actor_parent_ros_name.end()) {
117 it->second.push_back(parent);
118 } else {
119 _actor_parent_ros_name.insert({actor, {parent}});
120 }
121}
122
123void ROS2::RemoveActorRosName(void *actor) {
124 _actor_ros_name.erase(actor);
125 _actor_parent_ros_name.erase(actor);
126
127 _publishers.erase(actor);
128 _transforms.erase(actor);
129}
130
131void ROS2::UpdateActorRosName(void *actor, std::string ros_name) {
132 auto it = _actor_ros_name.find(actor);
133 if (it != _actor_ros_name.end()) {
134 it->second = ros_name;
135 }
136}
137
138std::string ROS2::GetActorRosName(void *actor) {
139 auto it = _actor_ros_name.find(actor);
140 if (it != _actor_ros_name.end()) {
141 return it->second;
142 } else {
143 return std::string("");
144 }
145}
146
147std::string ROS2::GetActorParentRosName(void *actor) {
148 auto it = _actor_parent_ros_name.find(actor);
149 if (it != _actor_parent_ros_name.end())
150 {
151 const std::string current_actor_name = GetActorRosName(actor);
152 std::string parent_name;
153 for (auto parent_it = it->second.cbegin(); parent_it != it->second.cend(); ++parent_it)
154 {
155 const std::string name = GetActorRosName(*parent_it);
156 if (name == current_actor_name)
157 {
158 continue;
159 }
160 if (name.empty())
161 {
162 continue;
163 }
164 parent_name = name + '/' + parent_name;
165 }
166 if (parent_name.back() == '/')
167 parent_name.pop_back();
168 return parent_name;
169 }
170 else
171 return std::string("");
172}
173
174void ROS2::AddActorCallback(void* actor, std::string ros_name, ActorCallback callback) {
175 _actor_callbacks.insert({actor, std::move(callback)});
176
177 _controller.reset();
178 _controller = std::make_shared<CarlaEgoVehicleControlSubscriber>(actor, ros_name.c_str());
179 _controller->Init();
180}
181
182void ROS2::RemoveActorCallback(void* actor) {
183 _controller.reset();
184 _actor_callbacks.erase(actor);
185}
186
187std::pair<std::shared_ptr<CarlaPublisher>, std::shared_ptr<CarlaTransformPublisher>> ROS2::GetOrCreateSensor(int type, carla::streaming::detail::stream_id_type id, void* actor) {
188 auto it_publishers = _publishers.find(actor);
189 auto it_transforms = _transforms.find(actor);
190 std::shared_ptr<CarlaPublisher> publisher {};
191 std::shared_ptr<CarlaTransformPublisher> transform {};
192 if (it_publishers != _publishers.end()) {
193 publisher = it_publishers->second;
194 if (it_transforms != _transforms.end()) {
195 transform = it_transforms->second;
196 }
197 } else {
198 // 没找到传感器,创建一个给定类型
199 const std::string string_id = std::to_string(id);
200 std::string ros_name = GetActorRosName(actor);
201 std::string parent_ros_name = GetActorParentRosName(actor);
202 switch(type) {
204 if (ros_name == "collision__") {
205 ros_name.pop_back();
206 ros_name.pop_back();
207 ros_name += string_id;
208 UpdateActorRosName(actor, ros_name);
209 }
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()) {
212 _publishers.insert({actor, new_publisher});
213 publisher = new_publisher;
214 }
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()) {
217 _transforms.insert({actor, new_transform});
218 transform = new_transform;
219 }
220 } break;
222 if (ros_name == "depth__") {
223 ros_name.pop_back();
224 ros_name.pop_back();
225 ros_name += string_id;
226 UpdateActorRosName(actor, ros_name);
227 }
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()) {
230 _publishers.insert({actor, new_publisher});
231 publisher = new_publisher;
232 }
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()) {
235 _transforms.insert({actor, new_transform});
236 transform = new_transform;
237 }
238 } break;
240 if (ros_name == "normals__") {
241 ros_name.pop_back();
242 ros_name.pop_back();
243 ros_name += string_id;
244 UpdateActorRosName(actor, ros_name);
245 }
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()) {
248 _publishers.insert({actor, new_publisher});
249 publisher = new_publisher;
250 }
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()) {
253 _transforms.insert({actor, new_transform});
254 transform = new_transform;
255 }
256 } break;
257 case ESensors::DVSCamera: {
258 if (ros_name == "dvs__") {
259 ros_name.pop_back();
260 ros_name.pop_back();
261 ros_name += string_id;
262 UpdateActorRosName(actor, ros_name);
263 }
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()) {
266 _publishers.insert({actor, new_publisher});
267 publisher = new_publisher;
268 }
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()) {
271 _transforms.insert({actor, new_transform});
272 transform = new_transform;
273 }
274 } break;
276 if (ros_name == "gnss__") {
277 ros_name.pop_back();
278 ros_name.pop_back();
279 ros_name += string_id;
280 UpdateActorRosName(actor, ros_name);
281 }
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()) {
284 _publishers.insert({actor, new_publisher});
285 publisher = new_publisher;
286 }
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()) {
289 _transforms.insert({actor, new_transform});
290 transform = new_transform;
291 }
292 } break;
294 if (ros_name == "imu__") {
295 ros_name.pop_back();
296 ros_name.pop_back();
297 ros_name += string_id;
298 UpdateActorRosName(actor, ros_name);
299 }
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()) {
302 _publishers.insert({actor, new_publisher});
303 publisher = new_publisher;
304 }
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()) {
307 _transforms.insert({actor, new_transform});
308 transform = new_transform;
309 }
310 } break;
312 if (ros_name == "lane_invasion__") {
313 ros_name.pop_back();
314 ros_name.pop_back();
315 ros_name += string_id;
316 UpdateActorRosName(actor, ros_name);
317 }
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()) {
320 _publishers.insert({actor, new_publisher});
321 publisher = new_publisher;
322 }
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()) {
325 _transforms.insert({actor, new_transform});
326 transform = new_transform;
327 }
328 } break;
330 std::cerr << "Obstacle detection sensor does not have an available publisher" << std::endl;
331 } break;
333 if (ros_name == "optical_flow__") {
334 ros_name.pop_back();
335 ros_name.pop_back();
336 ros_name += string_id;
337 UpdateActorRosName(actor, ros_name);
338 }
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()) {
341 _publishers.insert({actor, new_publisher});
342 publisher = new_publisher;
343 }
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()) {
346 _transforms.insert({actor, new_transform});
347 transform = new_transform;
348 }
349 } break;
350 case ESensors::Radar: {
351 if (ros_name == "radar__") {
352 ros_name.pop_back();
353 ros_name.pop_back();
354 ros_name += string_id;
355 UpdateActorRosName(actor, ros_name);
356 }
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()) {
359 _publishers.insert({actor, new_publisher});
360 publisher = new_publisher;
361 }
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()) {
364 _transforms.insert({actor, new_transform});
365 transform = new_transform;
366 }
367 } break;
369 if (ros_name == "ray_cast_semantic__") {
370 ros_name.pop_back();
371 ros_name.pop_back();
372 ros_name += string_id;
373 UpdateActorRosName(actor, ros_name);
374 }
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()) {
377 _publishers.insert({actor, new_publisher});
378 publisher = new_publisher;
379 }
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()) {
382 _transforms.insert({actor, new_transform});
383 transform = new_transform;
384 }
385 } break;
387 if (ros_name == "ray_cast__") {
388 ros_name.pop_back();
389 ros_name.pop_back();
390 ros_name += string_id;
391 UpdateActorRosName(actor, ros_name);
392 }
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()) {
395 _publishers.insert({actor, new_publisher});
396 publisher = new_publisher;
397 }
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()) {
400 _transforms.insert({actor, new_transform});
401 transform = new_transform;
402 }
403 } break;
404 case ESensors::RssSensor: {
405 std::cerr << "RSS sensor does not have an available publisher" << std::endl;
406 } break;
408 if (ros_name == "rgb__") {
409 ros_name.pop_back();
410 ros_name.pop_back();
411 ros_name += string_id;
412 UpdateActorRosName(actor, ros_name);
413 }
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()) {
416 _publishers.insert({actor, new_publisher});
417 publisher = new_publisher;
418 }
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()) {
421 _transforms.insert({actor, new_transform});
422 transform = new_transform;
423 }
424 } break;
426 if (ros_name == "semantic_segmentation__") {
427 ros_name.pop_back();
428 ros_name.pop_back();
429 ros_name += string_id;
430 UpdateActorRosName(actor, ros_name);
431 }
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()) {
434 _publishers.insert({actor, new_publisher});
435 publisher = new_publisher;
436 }
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()) {
439 _transforms.insert({actor, new_transform});
440 transform = new_transform;
441 }
442 } break;
444 if (ros_name == "instance_segmentation__") {
445 ros_name.pop_back();
446 ros_name.pop_back();
447 ros_name += string_id;
448 UpdateActorRosName(actor, ros_name);
449 }
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()) {
452 _publishers.insert({actor, new_publisher});
453 publisher = new_publisher;
454 }
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()) {
457 _transforms.insert({actor, new_transform});
458 transform = new_transform;
459 }
460 } break;
462 std::cerr << "World obserser does not have an available publisher" << std::endl;
463 } break;
465 std::cerr << "Camera GBuffer uint8 does not have an available publisher" << std::endl;
466 } break;
468 std::cerr << "Camera GBuffer float does not have an available publisher" << std::endl;
469 } break;
470 default: {
471 std::cerr << "Unknown sensor type" << std::endl;
472 }
473 }
474 }
475 return { publisher, transform };
476}
477
479 uint64_t sensor_type,
481 const carla::geom::Transform sensor_transform,
482 int W, int H, float Fov,
483 const carla::SharedBufferView buffer,
484 void *actor) {
485
486 switch (sensor_type) {
488 log_info("Sensor Collision to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
489 break;
491 {
492 log_info("Sensor DepthCamera to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
493 auto sensors = GetOrCreateSensor(ESensors::DepthCamera, stream_id, actor);
494 if (sensors.first) {
495 std::shared_ptr<CarlaDepthCameraPublisher> publisher = std::dynamic_pointer_cast<CarlaDepthCameraPublisher>(sensors.first);
497 reinterpret_cast<const carla::sensor::s11n::ImageSerializer::ImageHeader *>(buffer->data());
498 if (!header)
499 return;
500 if (!publisher->HasBeenInitialized())
501 publisher->InitInfoData(0, 0, H, W, Fov, true);
502 publisher->SetImageData(_seconds, _nanoseconds, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset));
503 publisher->SetCameraInfoData(_seconds, _nanoseconds);
504 publisher->Publish();
505 }
506 if (sensors.second) {
507 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
508 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
509 publisher->Publish();
510 }
511 }
512 break;
514 log_info("Sensor NormalsCamera to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
515 {
516 auto sensors = GetOrCreateSensor(ESensors::NormalsCamera, stream_id, actor);
517 if (sensors.first) {
518 std::shared_ptr<CarlaNormalsCameraPublisher> publisher = std::dynamic_pointer_cast<CarlaNormalsCameraPublisher>(sensors.first);
520 reinterpret_cast<const carla::sensor::s11n::ImageSerializer::ImageHeader *>(buffer->data());
521 if (!header)
522 return;
523 if (!publisher->HasBeenInitialized())
524 publisher->InitInfoData(0, 0, H, W, Fov, true);
525 publisher->SetImageData(_seconds, _nanoseconds, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset));
526 publisher->SetCameraInfoData(_seconds, _nanoseconds);
527 publisher->Publish();
528 }
529 if (sensors.second) {
530 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
531 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
532 publisher->Publish();
533 }
534 }
535 break;
537 log_info("Sensor LaneInvasionSensor to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
538 {
539 auto sensors = GetOrCreateSensor(ESensors::LaneInvasionSensor, stream_id, actor);
540 if (sensors.first) {
541 std::shared_ptr<CarlaLineInvasionPublisher> publisher = std::dynamic_pointer_cast<CarlaLineInvasionPublisher>(sensors.first);
542 publisher->SetData(_seconds, _nanoseconds, (const int32_t*) buffer->data());
543 publisher->Publish();
544 }
545 if (sensors.second) {
546 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
547 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
548 publisher->Publish();
549 }
550 }
551 break;
553 log_info("Sensor OpticalFlowCamera to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
554 {
555 auto sensors = GetOrCreateSensor(ESensors::OpticalFlowCamera, stream_id, actor);
556 if (sensors.first) {
557 std::shared_ptr<CarlaOpticalFlowCameraPublisher> publisher = std::dynamic_pointer_cast<CarlaOpticalFlowCameraPublisher>(sensors.first);
559 reinterpret_cast<const carla::sensor::s11n::OpticalFlowImageSerializer::ImageHeader *>(buffer->data());
560 if (!header)
561 return;
562 if (!publisher->HasBeenInitialized())
563 publisher->InitInfoData(0, 0, H, W, Fov, true);
564 publisher->SetImageData(_seconds, _nanoseconds, header->height, header->width, (const float*) (buffer->data() + carla::sensor::s11n::OpticalFlowImageSerializer::header_offset));
565 publisher->SetCameraInfoData(_seconds, _nanoseconds);
566 publisher->Publish();
567 }
568 if (sensors.second) {
569 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
570 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
571 publisher->Publish();
572 }
573 }
574 break;
576 log_info("Sensor RssSensor to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
577 break;
579 {
580 log_info("Sensor SceneCaptureCamera to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
581 {
582 auto sensors = GetOrCreateSensor(ESensors::SceneCaptureCamera, stream_id, actor);
583 if (sensors.first) {
584 std::shared_ptr<CarlaRGBCameraPublisher> publisher = std::dynamic_pointer_cast<CarlaRGBCameraPublisher>(sensors.first);
586 reinterpret_cast<const carla::sensor::s11n::ImageSerializer::ImageHeader *>(buffer->data());
587 if (!header)
588 return;
589 if (!publisher->HasBeenInitialized())
590 publisher->InitInfoData(0, 0, H, W, Fov, true);
591 publisher->SetImageData(_seconds, _nanoseconds, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset));
592 publisher->SetCameraInfoData(_seconds, _nanoseconds);
593 publisher->Publish();
594 }
595 if (sensors.second) {
596 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
597 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
598 publisher->Publish();
599 }
600 }
601 break;
602 }
604 log_info("Sensor SemanticSegmentationCamera to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
605 {
606 auto sensors = GetOrCreateSensor(ESensors::SemanticSegmentationCamera, stream_id, actor);
607 if (sensors.first) {
608 std::shared_ptr<CarlaSSCameraPublisher> publisher = std::dynamic_pointer_cast<CarlaSSCameraPublisher>(sensors.first);
610 reinterpret_cast<const carla::sensor::s11n::ImageSerializer::ImageHeader *>(buffer->data());
611 if (!header)
612 return;
613 if (!publisher->HasBeenInitialized())
614 publisher->InitInfoData(0, 0, H, W, Fov, true);
615 publisher->SetImageData(_seconds, _nanoseconds, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset));
616 publisher->SetCameraInfoData(_seconds, _nanoseconds);
617 publisher->Publish();
618 }
619 if (sensors.second) {
620 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
621 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
622 publisher->Publish();
623 }
624 }
625 break;
627 log_info("Sensor InstanceSegmentationCamera to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
628 {
629 auto sensors = GetOrCreateSensor(ESensors::InstanceSegmentationCamera, stream_id, actor);
630 if (sensors.first) {
631 std::shared_ptr<CarlaISCameraPublisher> publisher = std::dynamic_pointer_cast<CarlaISCameraPublisher>(sensors.first);
633 reinterpret_cast<const carla::sensor::s11n::ImageSerializer::ImageHeader *>(buffer->data());
634 if (!header)
635 return;
636 if (!publisher->HasBeenInitialized())
637 publisher->InitInfoData(0, 0, H, W, Fov, true);
638 publisher->SetImageData(_seconds, _nanoseconds, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset));
639 publisher->SetCameraInfoData(_seconds, _nanoseconds);
640 publisher->Publish();
641 }
642 if (sensors.second) {
643 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
644 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
645 publisher->Publish();
646 }
647 }
648 break;
650 log_info("Sensor WorldObserver to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
651 break;
653 log_info("Sensor CameraGBufferUint8 to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
654 break;
656 log_info("Sensor CameraGBufferFloat to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
657 break;
658 default:
659 log_info("Sensor to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "buffer.", buffer->size());
660 }
661}
662
664 uint64_t sensor_type,
666 const carla::geom::Transform sensor_transform,
667 const carla::geom::GeoLocation &data,
668 void *actor) {
669 log_info("Sensor GnssSensor to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "geo.", data.latitude, data.longitude, data.altitude);
670 auto sensors = GetOrCreateSensor(ESensors::GnssSensor, stream_id, actor);
671 if (sensors.first) {
672 std::shared_ptr<CarlaGNSSPublisher> publisher = std::dynamic_pointer_cast<CarlaGNSSPublisher>(sensors.first);
673 publisher->SetData(_seconds, _nanoseconds, reinterpret_cast<const double*>(&data));
674 publisher->Publish();
675 }
676 if (sensors.second) {
677 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
678 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
679 publisher->Publish();
680 }
681}
682
684 uint64_t sensor_type,
686 const carla::geom::Transform sensor_transform,
687 carla::geom::Vector3D accelerometer,
688 carla::geom::Vector3D gyroscope,
689 float compass,
690 void *actor) {
691 log_info("Sensor InertialMeasurementUnit to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "imu.", accelerometer.x, gyroscope.x, compass);
692 auto sensors = GetOrCreateSensor(ESensors::InertialMeasurementUnit, stream_id, actor);
693 if (sensors.first) {
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();
697 }
698 if (sensors.second) {
699 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
700 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
701 publisher->Publish();
702 }
703}
704
706 uint64_t sensor_type,
708 const carla::geom::Transform sensor_transform,
709 const carla::SharedBufferView buffer,
710 int W, int H, float Fov,
711 void *actor) {
712 log_info("Sensor DVS to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id);
713 auto sensors = GetOrCreateSensor(ESensors::DVSCamera, stream_id, actor);
714 if (sensors.first) {
715 std::shared_ptr<CarlaDVSCameraPublisher> publisher = std::dynamic_pointer_cast<CarlaDVSCameraPublisher>(sensors.first);
717 reinterpret_cast<const carla::sensor::s11n::ImageSerializer::ImageHeader *>(buffer->data());
718 if (!header)
719 return;
720 if (!publisher->HasBeenInitialized())
721 publisher->InitInfoData(0, 0, H, W, Fov, true);
722 size_t elements = (buffer->size() - carla::sensor::s11n::ImageSerializer::header_offset) / sizeof(carla::sensor::data::DVSEvent);
723 publisher->SetImageData(_seconds, _nanoseconds, elements, header->height, header->width, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset));
724 publisher->SetCameraInfoData(_seconds, _nanoseconds);
725 publisher->SetPointCloudData(1, elements * sizeof(carla::sensor::data::DVSEvent), elements, (const uint8_t*) (buffer->data() + carla::sensor::s11n::ImageSerializer::header_offset));
726 publisher->Publish();
727 }
728 if (sensors.second) {
729 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
730 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
731 publisher->Publish();
732 }
733}
734
736 uint64_t sensor_type,
738 const carla::geom::Transform sensor_transform,
740 void *actor) {
741 log_info("Sensor Lidar to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "points.", data._points.size());
742 auto sensors = GetOrCreateSensor(ESensors::RayCastLidar, stream_id, actor);
743 if (sensors.first) {
744 std::shared_ptr<CarlaLidarPublisher> publisher = std::dynamic_pointer_cast<CarlaLidarPublisher>(sensors.first);
745 size_t width = data._points.size();
746 size_t height = 1;
747 publisher->SetData(_seconds, _nanoseconds, height, width, (float*)data._points.data());
748 publisher->Publish();
749 }
750 if (sensors.second) {
751 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
752 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
753 publisher->Publish();
754 }
755}
756
758 uint64_t sensor_type,
760 const carla::geom::Transform sensor_transform,
762 void *actor) {
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());
765 auto sensors = GetOrCreateSensor(ESensors::RayCastSemanticLidar, stream_id, actor);
766 if (sensors.first) {
767 std::shared_ptr<CarlaSemanticLidarPublisher> publisher = std::dynamic_pointer_cast<CarlaSemanticLidarPublisher>(sensors.first);
768 size_t width = data._ser_points.size();
769 size_t height = 1;
770 publisher->SetData(_seconds, _nanoseconds, 6, height, width, (float*)data._ser_points.data());
771 publisher->Publish();
772 }
773 if (sensors.second) {
774 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
775 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
776 publisher->Publish();
777 }
778}
779
781 uint64_t sensor_type,
783 const carla::geom::Transform sensor_transform,
785 void *actor) {
786 log_info("Sensor Radar to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "points.", data._detections.size());
787 auto sensors = GetOrCreateSensor(ESensors::Radar, stream_id, actor);
788 if (sensors.first) {
789 std::shared_ptr<CarlaRadarPublisher> publisher = std::dynamic_pointer_cast<CarlaRadarPublisher>(sensors.first);
790 size_t elements = data.GetDetectionCount();
791 size_t width = elements * sizeof(carla::sensor::data::RadarDetection);
792 size_t height = 1;
793 publisher->SetData(_seconds, _nanoseconds, height, width, elements, (const uint8_t*)data._detections.data());
794 publisher->Publish();
795 }
796 if (sensors.second) {
797 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
798 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
799 publisher->Publish();
800 }
801}
802
804 uint64_t sensor_type,
806 const carla::geom::Transform sensor_transform,
807 AActor *first_ctor,
808 AActor *second_actor,
809 float distance,
810 void *actor) {
811 log_info("Sensor ObstacleDetector to ROS data: frame.", _frame, "sensor.", sensor_type, "stream.", stream_id, "distance.", distance);
812}
813
815 uint64_t sensor_type,
817 const carla::geom::Transform sensor_transform,
818 uint32_t other_actor,
819 carla::geom::Vector3D impulse,
820 void* actor) {
821 auto sensors = GetOrCreateSensor(ESensors::CollisionSensor, stream_id, actor);
822 if (sensors.first) {
823 std::shared_ptr<CarlaCollisionPublisher> publisher = std::dynamic_pointer_cast<CarlaCollisionPublisher>(sensors.first);
824 publisher->SetData(_seconds, _nanoseconds, other_actor, impulse.x, impulse.y, impulse.z);
825 publisher->Publish();
826 }
827 if (sensors.second) {
828 std::shared_ptr<CarlaTransformPublisher> publisher = std::dynamic_pointer_cast<CarlaTransformPublisher>(sensors.second);
829 publisher->SetData(_seconds, _nanoseconds, (const float*)&sensor_transform.location, (const float*)&sensor_transform.rotation);
830 publisher->Publish();
831 }
832}
833
835 for (auto& element : _publishers) {
836 element.second.reset();
837 }
838 for (auto& element : _transforms) {
839 element.second.reset();
840 }
841 _clock_publisher.reset();
842 _controller.reset();
843 _enabled = false;
844}
845
846} // namespace ros2
847} // namespace carla
std::unordered_map< void *, std::shared_ptr< CarlaTransformPublisher > > _transforms
Definition ROS2.h:161
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)
Definition ROS2.cpp:780
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)
Definition ROS2.cpp:705
static std::shared_ptr< ROS2 > _instance
Definition ROS2.h:150
std::string GetActorParentRosName(void *actor)
Definition ROS2.cpp:147
void AddActorCallback(void *actor, std::string ros_name, ActorCallback callback)
Definition ROS2.cpp:174
void Enable(bool enable)
Definition ROS2.cpp:73
void RemoveActorRosName(void *actor)
Definition ROS2.cpp:123
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)
Definition ROS2.cpp:683
void Shutdown()
Definition ROS2.cpp:834
std::string GetActorRosName(void *actor)
Definition ROS2.cpp:138
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)
Definition ROS2.cpp:803
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)
Definition ROS2.cpp:478
std::unordered_map< void *, ActorCallback > _actor_callbacks
Definition ROS2.h:163
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)
Definition ROS2.cpp:757
std::shared_ptr< CarlaClockPublisher > _clock_publisher
Definition ROS2.h:159
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)
Definition ROS2.cpp:814
std::shared_ptr< CarlaEgoVehicleControlSubscriber > _controller
Definition ROS2.h:158
void AddActorRosName(void *actor, std::string ros_name)
Definition ROS2.cpp:110
void UpdateActorRosName(void *actor, std::string ros_name)
Definition ROS2.cpp:131
uint32_t _nanoseconds
Definition ROS2.h:155
std::unordered_map< void *, std::vector< void * > > _actor_parent_ros_name
Definition ROS2.h:157
void AddActorParentRosName(void *actor, void *parent)
Definition ROS2.cpp:114
void SetTimestamp(double timestamp)
Definition ROS2.cpp:99
void RemoveActorCallback(void *actor)
Definition ROS2.cpp:182
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)
Definition ROS2.cpp:735
void SetFrame(uint64_t frame)
Definition ROS2.cpp:80
int32_t _seconds
Definition ROS2.h:154
std::pair< std::shared_ptr< CarlaPublisher >, std::shared_ptr< CarlaTransformPublisher > > GetOrCreateSensor(int type, carla::streaming::detail::stream_id_type id, void *actor)
Definition ROS2.cpp:187
std::unordered_map< void *, std::string > _actor_ros_name
Definition ROS2.h:156
std::unordered_map< void *, std::shared_ptr< CarlaPublisher > > _publishers
Definition ROS2.h:160
uint64_t _frame
Definition ROS2.h:153
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)
Definition ROS2.cpp:663
std::vector< float > _points
Definition LidarData.h:111
size_t GetDetectionCount() const
Returns the number of current detections.
Definition RadarData.h:58
std::vector< RadarDetection > _detections
Definition RadarData.h:74
std::vector< SemanticLidarDetection > _ser_points
std::function< void(void *actor, ROS2CallbackData data)> ActorCallback
@ InstanceSegmentationCamera
Definition ROS2.cpp:67
@ RssSensor
Definition ROS2.cpp:64
@ NormalsCamera
Definition ROS2.cpp:54
@ RayCastSemanticLidar
Definition ROS2.cpp:62
@ GnssSensor
Definition ROS2.cpp:56
@ SceneCaptureCamera
Definition ROS2.cpp:65
@ CameraGBufferUint8
Definition ROS2.cpp:69
@ DVSCamera
Definition ROS2.cpp:55
@ RayCastLidar
Definition ROS2.cpp:63
@ SemanticSegmentationCamera
Definition ROS2.cpp:66
@ DepthCamera
Definition ROS2.cpp:53
@ CameraGBufferFloat
Definition ROS2.cpp:70
@ WorldObserver
Definition ROS2.cpp:68
@ InertialMeasurementUnit
Definition ROS2.cpp:57
@ OpticalFlowCamera
Definition ROS2.cpp:60
@ CollisionSensor
Definition ROS2.cpp:52
@ ObstacleDetectionSensor
Definition ROS2.cpp:59
@ LaneInvasionSensor
Definition ROS2.cpp:58
uint32_t stream_id_type
Definition Types.h:18
This file contains definitions of common data structures used in traffic manager.
Definition Carla.cpp:133
std::shared_ptr< BufferView > SharedBufferView
Definition BufferView.h:151
static void log_info(Args &&... args)
Definition Logging.h:82