CARLA
 
载入中...
搜索中...
未找到
CarlaDVSCameraPublisher.cpp
浏览该文件的文档.
1#define _GLIBCXX_USE_CXX11_ABI 0
2
4
5#include <string>
6
8
13
14#include <fastdds/dds/domain/DomainParticipant.hpp>
15#include <fastdds/dds/publisher/Publisher.hpp>
16#include <fastdds/dds/topic/Topic.hpp>
17#include <fastdds/dds/publisher/DataWriter.hpp>
18#include <fastdds/dds/topic/TypeSupport.hpp>
19
20#include <fastdds/dds/domain/qos/DomainParticipantQos.hpp>
21#include <fastdds/dds/domain/DomainParticipantFactory.hpp>
22#include <fastdds/dds/publisher/qos/PublisherQos.hpp>
23#include <fastdds/dds/topic/qos/TopicQos.hpp>
24
25#include <fastrtps/attributes/ParticipantAttributes.h>
26#include <fastrtps/qos/QosPolicies.h>
27#include <fastdds/dds/publisher/qos/DataWriterQos.hpp>
28#include <fastdds/dds/publisher/DataWriterListener.hpp>
29
30
31namespace carla {
32namespace ros2 {
33
34 namespace efd = eprosima::fastdds::dds;
35 using erc = eprosima::fastrtps::types::ReturnCode_t;
36
38 efd::DomainParticipant* _participant { nullptr };
39 efd::Publisher* _publisher { nullptr };
40 efd::Topic* _topic { nullptr };
41 efd::DataWriter* _datawriter { nullptr };
42 efd::TypeSupport _type { new sensor_msgs::msg::ImagePubSubType() };
45 };
46
47 struct CarlaCameraInfoPublisherImpl {
48 efd::DomainParticipant* _participant { nullptr };
49 efd::Publisher* _publisher { nullptr };
50 efd::Topic* _topic { nullptr };
51 efd::DataWriter* _datawriter { nullptr };
52 efd::TypeSupport _type { new sensor_msgs::msg::CameraInfoPubSubType() };
53 CarlaListener _listener {};
54 bool _init {false};
56 };
57
59 efd::DomainParticipant* _participant { nullptr };
60 efd::Publisher* _publisher { nullptr };
61 efd::Topic* _topic { nullptr };
62 efd::DataWriter* _datawriter { nullptr };
66 };
67
69 return _info->_init;
70 }
71
72 void CarlaDVSCameraPublisher::InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify) {
73 _info->_ci = std::move(sensor_msgs::msg::CameraInfo(height, width, fov));
74 SetInfoRegionOfInterest(x_offset, y_offset, height, width, do_rectify);
75 _info->_init = true;
76 }
77
79 return InitImage() && InitInfo() && InitPointCloud();
80 }
81
83 if (_impl->_type == nullptr) {
84 std::cerr << "Invalid TypeSupport" << std::endl;
85 return false;
86 }
87
88 efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT;
89 pqos.name(_name);
90 auto factory = efd::DomainParticipantFactory::get_instance();
91 _impl->_participant = factory->create_participant(0, pqos);
92 if (_impl->_participant == nullptr) {
93 std::cerr << "Failed to create DomainParticipant" << std::endl;
94 return false;
95 }
96 _impl->_type.register_type(_impl->_participant);
97
98 efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT;
99 _impl->_publisher = _impl->_participant->create_publisher(pubqos, nullptr);
100 if (_impl->_publisher == nullptr) {
101 std::cerr << "Failed to create Publisher" << std::endl;
102 return false;
103 }
104
105 efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT;
106 const std::string publisher_type {"/image"};
107 const std::string base { "rt/carla/" };
108 std::string topic_name = base;
109 if (!_parent.empty())
110 topic_name += _parent + "/";
111 topic_name += _name;
112 topic_name += publisher_type;
113 _impl->_topic = _impl->_participant->create_topic(topic_name, _impl->_type->getName(), tqos);
114 if (_impl->_topic == nullptr) {
115 std::cerr << "Failed to create Topic" << std::endl;
116 return false;
117 }
118
119 efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT;
120 wqos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
121 efd::DataWriterListener* listener = (efd::DataWriterListener*)_impl->_listener._impl.get();
122 _impl->_datawriter = _impl->_publisher->create_datawriter(_impl->_topic, wqos, listener);
123 if (_impl->_datawriter == nullptr) {
124 std::cerr << "Failed to create DataWriter" << std::endl;
125 return false;
126 }
128 return true;
129 }
130
132 if (_info->_type == nullptr) {
133 std::cerr << "Invalid TypeSupport" << std::endl;
134 return false;
135 }
136
137 efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT;
138 pqos.name(_name);
139 auto factory = efd::DomainParticipantFactory::get_instance();
140 _info->_participant = factory->create_participant(0, pqos);
141 if (_info->_participant == nullptr) {
142 std::cerr << "Failed to create DomainParticipant" << std::endl;
143 return false;
144 }
145 _info->_type.register_type(_info->_participant);
146
147 efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT;
148 _info->_publisher = _info->_participant->create_publisher(pubqos, nullptr);
149 if (_info->_publisher == nullptr) {
150 std::cerr << "Failed to create Publisher" << std::endl;
151 return false;
152 }
153
154 efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT;
155 const std::string publisher_type {"/camera_info"};
156 const std::string base { "rt/carla/" };
157 std::string topic_name = base;
158 if (!_parent.empty())
159 topic_name += _parent + "/";
160 topic_name += _name;
161 topic_name += publisher_type;
162 _info->_topic = _info->_participant->create_topic(topic_name, _info->_type->getName(), tqos);
163 if (_info->_topic == nullptr) {
164 std::cerr << "Failed to create Topic" << std::endl;
165 return false;
166 }
167 efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT;
168 efd::DataWriterListener* listener = (efd::DataWriterListener*)_info->_listener._impl.get();
169 _info->_datawriter = _info->_publisher->create_datawriter(_info->_topic, wqos, listener);
170 if (_info->_datawriter == nullptr) {
171 std::cerr << "Failed to create DataWriter" << std::endl;
172 return false;
173 }
174
176 return true;
177 }
178
180 if (_point_cloud->_type == nullptr) {
181 std::cerr << "Invalid TypeSupport" << std::endl;
182 return false;
183 }
184
185 efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT;
186 pqos.name(_name);
187 auto factory = efd::DomainParticipantFactory::get_instance();
188 _point_cloud->_participant = factory->create_participant(0, pqos);
189 if (_point_cloud->_participant == nullptr) {
190 std::cerr << "Failed to create DomainParticipant" << std::endl;
191 return false;
192 }
193 _point_cloud->_type.register_type(_point_cloud->_participant);
194
195 efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT;
196 _point_cloud->_publisher = _point_cloud->_participant->create_publisher(pubqos, nullptr);
197 if (_point_cloud->_publisher == nullptr) {
198 std::cerr << "Failed to create Publisher" << std::endl;
199 return false;
200 }
201
202 efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT;
203 const std::string publisher_type {"/point_cloud"};
204 const std::string base { "rt/carla/" };
205 std::string topic_name = base;
206 if (!_parent.empty())
207 topic_name += _parent + "/";
208 topic_name += _name;
209 topic_name += publisher_type;
210 _point_cloud->_topic = _point_cloud->_participant->create_topic(topic_name, _point_cloud->_type->getName(), tqos);
211 if (_point_cloud->_topic == nullptr) {
212 std::cerr << "Failed to create Topic" << std::endl;
213 return false;
214 }
215
216 efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT;
217 wqos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
218 efd::DataWriterListener* listener = (efd::DataWriterListener*)_point_cloud->_listener._impl.get();
219 _point_cloud->_datawriter = _point_cloud->_publisher->create_datawriter(_point_cloud->_topic, wqos, listener);
220 if (_point_cloud->_datawriter == nullptr) {
221 std::cerr << "Failed to create DataWriter" << std::endl;
222 return false;
223 }
225 return true;
226 }
227
231
233 eprosima::fastrtps::rtps::InstanceHandle_t instance_handle;
234 eprosima::fastrtps::types::ReturnCode_t rcode = _impl->_datawriter->write(& _impl->_image, instance_handle);
235 if (rcode == erc::ReturnCodeValue::RETCODE_OK) {
236 return true;
237 }
238 if (rcode == erc::ReturnCodeValue::RETCODE_ERROR) {
239 std::cerr << "RETCODE_ERROR" << std::endl;
240 return false;
241 }
242 if (rcode == erc::ReturnCodeValue::RETCODE_UNSUPPORTED) {
243 std::cerr << "RETCODE_UNSUPPORTED" << std::endl;
244 return false;
245 }
246 if (rcode == erc::ReturnCodeValue::RETCODE_BAD_PARAMETER) {
247 std::cerr << "RETCODE_BAD_PARAMETER" << std::endl;
248 return false;
249 }
250 if (rcode == erc::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET) {
251 std::cerr << "RETCODE_PRECONDITION_NOT_MET" << std::endl;
252 return false;
253 }
254 if (rcode == erc::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES) {
255 std::cerr << "RETCODE_OUT_OF_RESOURCES" << std::endl;
256 return false;
257 }
258 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ENABLED) {
259 std::cerr << "RETCODE_NOT_ENABLED" << std::endl;
260 return false;
261 }
262 if (rcode == erc::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY) {
263 std::cerr << "RETCODE_IMMUTABLE_POLICY" << std::endl;
264 return false;
265 }
266 if (rcode == erc::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY) {
267 std::cerr << "RETCODE_INCONSISTENT_POLICY" << std::endl;
268 return false;
269 }
270 if (rcode == erc::ReturnCodeValue::RETCODE_ALREADY_DELETED) {
271 std::cerr << "RETCODE_ALREADY_DELETED" << std::endl;
272 return false;
273 }
274 if (rcode == erc::ReturnCodeValue::RETCODE_TIMEOUT) {
275 std::cerr << "RETCODE_TIMEOUT" << std::endl;
276 return false;
277 }
278 if (rcode == erc::ReturnCodeValue::RETCODE_NO_DATA) {
279 std::cerr << "RETCODE_NO_DATA" << std::endl;
280 return false;
281 }
282 if (rcode == erc::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION) {
283 std::cerr << "RETCODE_ILLEGAL_OPERATION" << std::endl;
284 return false;
285 }
286 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY) {
287 std::cerr << "RETCODE_NOT_ALLOWED_BY_SECURITY" << std::endl;
288 return false;
289 }
290 std::cerr << "UNKNOWN" << std::endl;
291 return false;
292 }
293
295 eprosima::fastrtps::rtps::InstanceHandle_t instance_handle;
296 eprosima::fastrtps::types::ReturnCode_t rcode = _info->_datawriter->write(& _info->_ci, instance_handle);
297 if (rcode == erc::ReturnCodeValue::RETCODE_OK) {
298 return true;
299 }
300 if (rcode == erc::ReturnCodeValue::RETCODE_ERROR) {
301 std::cerr << "RETCODE_ERROR" << std::endl;
302 return false;
303 }
304 if (rcode == erc::ReturnCodeValue::RETCODE_UNSUPPORTED) {
305 std::cerr << "RETCODE_UNSUPPORTED" << std::endl;
306 return false;
307 }
308 if (rcode == erc::ReturnCodeValue::RETCODE_BAD_PARAMETER) {
309 std::cerr << "RETCODE_BAD_PARAMETER" << std::endl;
310 return false;
311 }
312 if (rcode == erc::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET) {
313 std::cerr << "RETCODE_PRECONDITION_NOT_MET" << std::endl;
314 return false;
315 }
316 if (rcode == erc::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES) {
317 std::cerr << "RETCODE_OUT_OF_RESOURCES" << std::endl;
318 return false;
319 }
320 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ENABLED) {
321 std::cerr << "RETCODE_NOT_ENABLED" << std::endl;
322 return false;
323 }
324 if (rcode == erc::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY) {
325 std::cerr << "RETCODE_IMMUTABLE_POLICY" << std::endl;
326 return false;
327 }
328 if (rcode == erc::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY) {
329 std::cerr << "RETCODE_INCONSISTENT_POLICY" << std::endl;
330 return false;
331 }
332 if (rcode == erc::ReturnCodeValue::RETCODE_ALREADY_DELETED) {
333 std::cerr << "RETCODE_ALREADY_DELETED" << std::endl;
334 return false;
335 }
336 if (rcode == erc::ReturnCodeValue::RETCODE_TIMEOUT) {
337 std::cerr << "RETCODE_TIMEOUT" << std::endl;
338 return false;
339 }
340 if (rcode == erc::ReturnCodeValue::RETCODE_NO_DATA) {
341 std::cerr << "RETCODE_NO_DATA" << std::endl;
342 return false;
343 }
344 if (rcode == erc::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION) {
345 std::cerr << "RETCODE_ILLEGAL_OPERATION" << std::endl;
346 return false;
347 }
348 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY) {
349 std::cerr << "RETCODE_NOT_ALLOWED_BY_SECURITY" << std::endl;
350 return false;
351 }
352 std::cerr << "UNKNOWN" << std::endl;
353 return false;
354 }
355
357 eprosima::fastrtps::rtps::InstanceHandle_t instance_handle;
358 eprosima::fastrtps::types::ReturnCode_t rcode = _point_cloud->_datawriter->write(&_point_cloud->_pc, instance_handle);
359 if (rcode == erc::ReturnCodeValue::RETCODE_OK) {
360 return true;
361 }
362 if (rcode == erc::ReturnCodeValue::RETCODE_ERROR) {
363 std::cerr << "RETCODE_ERROR" << std::endl;
364 return false;
365 }
366 if (rcode == erc::ReturnCodeValue::RETCODE_UNSUPPORTED) {
367 std::cerr << "RETCODE_UNSUPPORTED" << std::endl;
368 return false;
369 }
370 if (rcode == erc::ReturnCodeValue::RETCODE_BAD_PARAMETER) {
371 std::cerr << "RETCODE_BAD_PARAMETER" << std::endl;
372 return false;
373 }
374 if (rcode == erc::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET) {
375 std::cerr << "RETCODE_PRECONDITION_NOT_MET" << std::endl;
376 return false;
377 }
378 if (rcode == erc::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES) {
379 std::cerr << "RETCODE_OUT_OF_RESOURCES" << std::endl;
380 return false;
381 }
382 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ENABLED) {
383 std::cerr << "RETCODE_NOT_ENABLED" << std::endl;
384 return false;
385 }
386 if (rcode == erc::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY) {
387 std::cerr << "RETCODE_IMMUTABLE_POLICY" << std::endl;
388 return false;
389 }
390 if (rcode == erc::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY) {
391 std::cerr << "RETCODE_INCONSISTENT_POLICY" << std::endl;
392 return false;
393 }
394 if (rcode == erc::ReturnCodeValue::RETCODE_ALREADY_DELETED) {
395 std::cerr << "RETCODE_ALREADY_DELETED" << std::endl;
396 return false;
397 }
398 if (rcode == erc::ReturnCodeValue::RETCODE_TIMEOUT) {
399 std::cerr << "RETCODE_TIMEOUT" << std::endl;
400 return false;
401 }
402 if (rcode == erc::ReturnCodeValue::RETCODE_NO_DATA) {
403 std::cerr << "RETCODE_NO_DATA" << std::endl;
404 return false;
405 }
406 if (rcode == erc::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION) {
407 std::cerr << "RETCODE_ILLEGAL_OPERATION" << std::endl;
408 return false;
409 }
410 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY) {
411 std::cerr << "RETCODE_NOT_ALLOWED_BY_SECURITY" << std::endl;
412 return false;
413 }
414 std::cerr << "UNKNOWN" << std::endl;
415 return false;
416 }
417
418 void CarlaDVSCameraPublisher::SetImageData(int32_t seconds, uint32_t nanoseconds, size_t elements, size_t height, size_t width, const uint8_t* data) {
419 std::vector<uint8_t> im_data;
420 const size_t im_size = width * height * 3;
421 im_data.resize(im_size);
423 for (size_t i = 0; i < elements; ++i, ++vec_event) {
424 size_t index = (vec_event->y * width + vec_event->x) * 3 + (static_cast<int>(vec_event->pol) * 2);
425 im_data[index] = 255;
426 }
427
428 SetData(seconds, nanoseconds, height, width, std::move(im_data));
429 }
430
431 void CarlaDVSCameraPublisher::SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data) {
433 time.sec(seconds);
434 time.nanosec(nanoseconds);
435
437 header.stamp(std::move(time));
438 header.frame_id(_frame_id);
439 _impl->_image.header(header);
440 _info->_ci.header(header);
441 _point_cloud->_pc.header(header);
442
443 _impl->_image.width(width);
444 _impl->_image.height(height);
445 _impl->_image.encoding("bgr8"); //taken from the list of strings in include/sensor_msgs/image_encodings.h
446 _impl->_image.is_bigendian(0);
447 _impl->_image.step(_impl->_image.width() * sizeof(uint8_t) * 3);
448 _impl->_image.data(std::move(data)); //https://github.com/eProsima/Fast-DDS/issues/2330
449 }
450
451 void CarlaDVSCameraPublisher::SetCameraInfoData(int32_t seconds, uint32_t nanoseconds) {
453 time.sec(seconds);
454 time.nanosec(nanoseconds);
455
457 header.stamp(std::move(time));
458 header.frame_id(_frame_id);
459 }
460
461 void CarlaDVSCameraPublisher::SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify) {
463 roi.x_offset(x_offset);
464 roi.y_offset(y_offset);
465 roi.height(height);
466 roi.width(width);
467 roi.do_rectify(do_rectify);
468 _info->_ci.roi(roi);
469 }
470
471 void CarlaDVSCameraPublisher::SetPointCloudData(size_t height, size_t width, size_t elements, const uint8_t* data) {
472
473 std::vector<uint8_t> vector_data;
474 const size_t size = height * width;
475 vector_data.resize(size);
476 std::memcpy(&vector_data[0], &data[0], size);
477
479 descriptor1.name("x");
480 descriptor1.offset(0);
482 descriptor1.count(1);
484 descriptor2.name("y");
485 descriptor2.offset(2);
487 descriptor2.count(1);
489 descriptor3.name("t");
490 descriptor3.offset(4);
492 descriptor3.count(1);
494 descriptor3.name("pol");
495 descriptor3.offset(12);
497 descriptor3.count(1);
498
499 const size_t point_size = sizeof(carla::sensor::data::DVSEvent);
500 _point_cloud->_pc.width(width);
501 _point_cloud->_pc.height(height);
502 _point_cloud->_pc.is_bigendian(false);
503 _point_cloud->_pc.fields({descriptor1, descriptor2, descriptor3, descriptor4});
504 _point_cloud->_pc.point_step(point_size);
505 _point_cloud->_pc.row_step(width * point_size);
506 _point_cloud->_pc.is_dense(false); //True if there are not invalid points
507 _point_cloud->_pc.data(std::move(vector_data));
508 }
509
510 CarlaDVSCameraPublisher::CarlaDVSCameraPublisher(const char* ros_name, const char* parent) :
511 _impl(std::make_shared<CarlaDVSCameraPublisherImpl>()),
512 _info(std::make_shared<CarlaCameraInfoPublisherImpl>()),
513 _point_cloud(std::make_shared<CarlaPointCloudPublisherImpl>()) {
514 _name = ros_name;
515 _parent = parent;
516 }
517
519 if (!_impl)
520 return;
521
522 if (_impl->_datawriter)
523 _impl->_publisher->delete_datawriter(_impl->_datawriter);
524
525 if (_impl->_publisher)
526 _impl->_participant->delete_publisher(_impl->_publisher);
527
528 if (_impl->_topic)
529 _impl->_participant->delete_topic(_impl->_topic);
530
531 if (_impl->_participant)
532 efd::DomainParticipantFactory::get_instance()->delete_participant(_impl->_participant);
533
534 if (!_info)
535 return;
536
537 if (_info->_datawriter)
538 _info->_publisher->delete_datawriter(_info->_datawriter);
539
540 if (_info->_publisher)
541 _info->_participant->delete_publisher(_info->_publisher);
542
543 if (_info->_topic)
544 _info->_participant->delete_topic(_info->_topic);
545
546 if (_info->_participant)
547 efd::DomainParticipantFactory::get_instance()->delete_participant(_info->_participant);
548
549 if (!_point_cloud)
550 return;
551
552 if (_point_cloud->_datawriter)
553 _point_cloud->_publisher->delete_datawriter(_point_cloud->_datawriter);
554
555 if (_point_cloud->_publisher)
556 _point_cloud->_participant->delete_publisher(_point_cloud->_publisher);
557
558 if (_point_cloud->_topic)
559 _point_cloud->_participant->delete_topic(_point_cloud->_topic);
560
561 if (_point_cloud->_participant)
562 efd::DomainParticipantFactory::get_instance()->delete_participant(_point_cloud->_participant);
563 }
564
566 _frame_id = other._frame_id;
567 _name = other._name;
568 _parent = other._parent;
569 _impl = other._impl;
570 _info = other._info;
572 }
573
575 _frame_id = other._frame_id;
576 _name = other._name;
577 _parent = other._parent;
578 _impl = other._impl;
579 _info = other._info;
581
582 return *this;
583 }
584
586 _frame_id = std::move(other._frame_id);
587 _name = std::move(other._name);
588 _parent = std::move(other._parent);
589 _impl = std::move(other._impl);
590 _info = std::move(other._info);
591 _point_cloud = std::move(other._point_cloud);
592 }
593
595 _frame_id = std::move(other._frame_id);
596 _name = std::move(other._name);
597 _parent = std::move(other._parent);
598 _impl = std::move(other._impl);
599 _info = std::move(other._info);
600 _point_cloud = std::move(other._point_cloud);
601
602 return *this;
603 }
604}
605}
This class represents the structure Time defined by the user in the IDL file.
eProsima_user_DllExport void nanosec(uint32_t _nanosec)
This function sets a value in member nanosec
Definition Time.cpp:161
eProsima_user_DllExport void sec(int32_t _sec)
This function sets a value in member sec
Definition Time.cpp:133
void SetPointCloudData(size_t height, size_t width, size_t elements, const uint8_t *data)
CarlaDVSCameraPublisher & operator=(const CarlaDVSCameraPublisher &)
CarlaDVSCameraPublisher(const char *ros_name="", const char *parent="")
std::shared_ptr< CarlaCameraInfoPublisherImpl > _info
std::shared_ptr< CarlaDVSCameraPublisherImpl > _impl
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t elements, size_t height, size_t width, const uint8_t *data)
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
std::shared_ptr< CarlaPointCloudPublisherImpl > _point_cloud
const std::string & parent() const
This class represents the TopicDataType of the type CameraInfo defined by the user in the IDL file.
This class represents the structure CameraInfo defined by the user in the IDL file.
Definition CameraInfo.h:74
This class represents the TopicDataType of the type Image defined by the user in the IDL file.
This class represents the structure Image defined by the user in the IDL file.
This class represents the TopicDataType of the type PointCloud2 defined by the user in the IDL file.
This class represents the structure PointCloud2 defined by the user in the IDL file.
Definition PointCloud2.h:74
This class represents the structure PointField defined by the user in the IDL file.
Definition PointField.h:80
eProsima_user_DllExport void count(uint32_t _count)
This function sets a value in member count
eProsima_user_DllExport void offset(uint32_t _offset)
This function sets a value in member offset
eProsima_user_DllExport void name(const std::string &_name)
This function copies the value in member name
eProsima_user_DllExport void datatype(uint8_t _datatype)
This function sets a value in member datatype
This class represents the structure RegionOfInterest defined by the user in the IDL file.
eProsima_user_DllExport void y_offset(uint32_t _y_offset)
This function sets a value in member y_offset
eProsima_user_DllExport void width(uint32_t _width)
This function sets a value in member width
eProsima_user_DllExport void height(uint32_t _height)
This function sets a value in member height
eProsima_user_DllExport void x_offset(uint32_t _x_offset)
This function sets a value in member x_offset
eProsima_user_DllExport void do_rectify(bool _do_rectify)
This function sets a value in member do_rectify
This class represents the structure Header defined by the user in the IDL file.
Definition Header.h:73
eProsima_user_DllExport void stamp(const builtin_interfaces::msg::Time &_stamp)
This function copies the value in member stamp
Definition Header.cpp:131
eProsima_user_DllExport void frame_id(const std::string &_frame_id)
This function copies the value in member frame_id
Definition Header.cpp:168
eprosima::fastrtps::types::ReturnCode_t erc
This file contains definitions of common data structures used in traffic manager.
Definition Carla.cpp:133
const uint8_t PointField__UINT16
Definition PointField.h:69
const uint8_t PointField__INT8
Definition PointField.h:66
const uint8_t PointField__FLOAT64
Definition PointField.h:73