CARLA
CarlaSSCameraPublisher.cpp
Go to the documentation of this file.
1 #define _GLIBCXX_USE_CXX11_ABI 0
2 
4 
5 #include <string>
6 
10 
11 #include <fastdds/dds/domain/DomainParticipant.hpp>
12 #include <fastdds/dds/publisher/Publisher.hpp>
13 #include <fastdds/dds/topic/Topic.hpp>
14 #include <fastdds/dds/publisher/DataWriter.hpp>
15 #include <fastdds/dds/topic/TypeSupport.hpp>
16 
17 #include <fastdds/dds/domain/qos/DomainParticipantQos.hpp>
18 #include <fastdds/dds/domain/DomainParticipantFactory.hpp>
19 #include <fastdds/dds/publisher/qos/PublisherQos.hpp>
20 #include <fastdds/dds/topic/qos/TopicQos.hpp>
21 
22 #include <fastrtps/attributes/ParticipantAttributes.h>
23 #include <fastrtps/qos/QosPolicies.h>
24 #include <fastdds/dds/publisher/qos/DataWriterQos.hpp>
25 #include <fastdds/dds/publisher/DataWriterListener.hpp>
26 
27 namespace carla {
28 namespace ros2 {
29 
30  namespace efd = eprosima::fastdds::dds;
31  using erc = eprosima::fastrtps::types::ReturnCode_t;
32 
34  efd::DomainParticipant* _participant { nullptr };
35  efd::Publisher* _publisher { nullptr };
36  efd::Topic* _topic { nullptr };
37  efd::DataWriter* _datawriter { nullptr };
38  efd::TypeSupport _type { new sensor_msgs::msg::ImagePubSubType() };
41  };
42 
44  efd::DomainParticipant* _participant { nullptr };
45  efd::Publisher* _publisher { nullptr };
46  efd::Topic* _topic { nullptr };
47  efd::DataWriter* _datawriter { nullptr };
48  efd::TypeSupport _type { new sensor_msgs::msg::CameraInfoPubSubType() };
50  bool _init {false};
52  };
53 
55  return _impl_info->_init;
56  }
57 
58  void CarlaSSCameraPublisher::InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify) {
59  _impl_info->_info = std::move(sensor_msgs::msg::CameraInfo(height, width, fov));
60  SetInfoRegionOfInterest(x_offset, y_offset, height, width, do_rectify);
61  _impl_info->_init = true;
62  }
63 
65  return InitImage() && InitInfo();
66  }
67 
69  if (_impl->_type == nullptr) {
70  std::cerr << "Invalid TypeSupport" << std::endl;
71  return false;
72  }
73  efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT;
74  pqos.name(_name);
75  auto factory = efd::DomainParticipantFactory::get_instance();
76  _impl->_participant = factory->create_participant(0, pqos);
77  if (_impl->_participant == nullptr) {
78  std::cerr << "Failed to create DomainParticipant" << std::endl;
79  return false;
80  }
81  _impl->_type.register_type(_impl->_participant);
82 
83  efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT;
84  _impl->_publisher = _impl->_participant->create_publisher(pubqos, nullptr);
85  if (_impl->_publisher == nullptr) {
86  std::cerr << "Failed to create Publisher" << std::endl;
87  return false;
88  }
89 
90  efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT;
91  const std::string publisher_type {"/image"};
92  const std::string base { "rt/carla/" };
93  std::string topic_name = base;
94  if (!_parent.empty())
95  topic_name += _parent + "/";
96  topic_name += _name;
97  topic_name += publisher_type;
98  _impl->_topic = _impl->_participant->create_topic(topic_name, _impl->_type->getName(), tqos);
99  if (_impl->_topic == nullptr) {
100  std::cerr << "Failed to create Topic" << std::endl;
101  return false;
102  }
103 
104  efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT;
105  wqos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
106  efd::DataWriterListener* listener = (efd::DataWriterListener*)_impl->_listener._impl.get();
107  _impl->_datawriter = _impl->_publisher->create_datawriter(_impl->_topic, wqos, listener);
108  if (_impl->_datawriter == nullptr) {
109  std::cerr << "Failed to create DataWriter" << std::endl;
110  return false;
111  }
112  _frame_id = _name;
113  return true;
114  }
115 
117  if (_impl_info->_type == nullptr) {
118  std::cerr << "Invalid TypeSupport" << std::endl;
119  return false;
120  }
121 
122  efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT;
123  pqos.name(_name);
124  auto factory = efd::DomainParticipantFactory::get_instance();
125  _impl_info->_participant = factory->create_participant(0, pqos);
126  if (_impl_info->_participant == nullptr) {
127  std::cerr << "Failed to create DomainParticipant" << std::endl;
128  return false;
129  }
130  _impl_info->_type.register_type(_impl_info->_participant);
131 
132  efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT;
133  _impl_info->_publisher = _impl_info->_participant->create_publisher(pubqos, nullptr);
134  if (_impl_info->_publisher == nullptr) {
135  std::cerr << "Failed to create Publisher" << std::endl;
136  return false;
137  }
138 
139  efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT;
140  const std::string publisher_type {"/camera_info"};
141  const std::string base { "rt/carla/" };
142  std::string topic_name = base;
143  if (!_parent.empty())
144  topic_name += _parent + "/";
145  topic_name += _name;
146  topic_name += publisher_type;
147  _impl_info->_topic = _impl_info->_participant->create_topic(topic_name, _impl_info->_type->getName(), tqos);
148  if (_impl_info->_topic == nullptr) {
149  std::cerr << "Failed to create Topic" << std::endl;
150  return false;
151  }
152  efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT;
153  efd::DataWriterListener* listener = (efd::DataWriterListener*)_impl_info->_listener._impl.get();
154  _impl_info->_datawriter = _impl_info->_publisher->create_datawriter(_impl_info->_topic, wqos, listener);
155  if (_impl_info->_datawriter == nullptr) {
156  std::cerr << "Failed to create DataWriter" << std::endl;
157  return false;
158  }
159 
160  _frame_id = _name;
161  return true;
162  }
163 
165  return PublishImage() && PublishInfo();
166  }
167 
170  eprosima::fastrtps::types::ReturnCode_t rcode = _impl->_datawriter->write(&_impl->_image, instance_handle);
171  if (rcode == erc::ReturnCodeValue::RETCODE_OK) {
172  return true;
173  }
174  if (rcode == erc::ReturnCodeValue::RETCODE_ERROR) {
175  std::cerr << "RETCODE_ERROR" << std::endl;
176  return false;
177  }
178  if (rcode == erc::ReturnCodeValue::RETCODE_UNSUPPORTED) {
179  std::cerr << "RETCODE_UNSUPPORTED" << std::endl;
180  return false;
181  }
182  if (rcode == erc::ReturnCodeValue::RETCODE_BAD_PARAMETER) {
183  std::cerr << "RETCODE_BAD_PARAMETER" << std::endl;
184  return false;
185  }
186  if (rcode == erc::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET) {
187  std::cerr << "RETCODE_PRECONDITION_NOT_MET" << std::endl;
188  return false;
189  }
190  if (rcode == erc::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES) {
191  std::cerr << "RETCODE_OUT_OF_RESOURCES" << std::endl;
192  return false;
193  }
194  if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ENABLED) {
195  std::cerr << "RETCODE_NOT_ENABLED" << std::endl;
196  return false;
197  }
198  if (rcode == erc::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY) {
199  std::cerr << "RETCODE_IMMUTABLE_POLICY" << std::endl;
200  return false;
201  }
202  if (rcode == erc::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY) {
203  std::cerr << "RETCODE_INCONSISTENT_POLICY" << std::endl;
204  return false;
205  }
206  if (rcode == erc::ReturnCodeValue::RETCODE_ALREADY_DELETED) {
207  std::cerr << "RETCODE_ALREADY_DELETED" << std::endl;
208  return false;
209  }
210  if (rcode == erc::ReturnCodeValue::RETCODE_TIMEOUT) {
211  std::cerr << "RETCODE_TIMEOUT" << std::endl;
212  return false;
213  }
214  if (rcode == erc::ReturnCodeValue::RETCODE_NO_DATA) {
215  std::cerr << "RETCODE_NO_DATA" << std::endl;
216  return false;
217  }
218  if (rcode == erc::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION) {
219  std::cerr << "RETCODE_ILLEGAL_OPERATION" << std::endl;
220  return false;
221  }
222  if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY) {
223  std::cerr << "RETCODE_NOT_ALLOWED_BY_SECURITY" << std::endl;
224  return false;
225  }
226  std::cerr << "UNKNOWN" << std::endl;
227  return false;
228  }
229 
232  eprosima::fastrtps::types::ReturnCode_t rcode = _impl_info->_datawriter->write(&_impl_info->_info, instance_handle);
233  if (rcode == erc::ReturnCodeValue::RETCODE_OK) {
234  return true;
235  }
236  if (rcode == erc::ReturnCodeValue::RETCODE_ERROR) {
237  std::cerr << "RETCODE_ERROR" << std::endl;
238  return false;
239  }
240  if (rcode == erc::ReturnCodeValue::RETCODE_UNSUPPORTED) {
241  std::cerr << "RETCODE_UNSUPPORTED" << std::endl;
242  return false;
243  }
244  if (rcode == erc::ReturnCodeValue::RETCODE_BAD_PARAMETER) {
245  std::cerr << "RETCODE_BAD_PARAMETER" << std::endl;
246  return false;
247  }
248  if (rcode == erc::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET) {
249  std::cerr << "RETCODE_PRECONDITION_NOT_MET" << std::endl;
250  return false;
251  }
252  if (rcode == erc::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES) {
253  std::cerr << "RETCODE_OUT_OF_RESOURCES" << std::endl;
254  return false;
255  }
256  if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ENABLED) {
257  std::cerr << "RETCODE_NOT_ENABLED" << std::endl;
258  return false;
259  }
260  if (rcode == erc::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY) {
261  std::cerr << "RETCODE_IMMUTABLE_POLICY" << std::endl;
262  return false;
263  }
264  if (rcode == erc::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY) {
265  std::cerr << "RETCODE_INCONSISTENT_POLICY" << std::endl;
266  return false;
267  }
268  if (rcode == erc::ReturnCodeValue::RETCODE_ALREADY_DELETED) {
269  std::cerr << "RETCODE_ALREADY_DELETED" << std::endl;
270  return false;
271  }
272  if (rcode == erc::ReturnCodeValue::RETCODE_TIMEOUT) {
273  std::cerr << "RETCODE_TIMEOUT" << std::endl;
274  return false;
275  }
276  if (rcode == erc::ReturnCodeValue::RETCODE_NO_DATA) {
277  std::cerr << "RETCODE_NO_DATA" << std::endl;
278  return false;
279  }
280  if (rcode == erc::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION) {
281  std::cerr << "RETCODE_ILLEGAL_OPERATION" << std::endl;
282  return false;
283  }
284  if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY) {
285  std::cerr << "RETCODE_NOT_ALLOWED_BY_SECURITY" << std::endl;
286  return false;
287  }
288  std::cerr << "UNKNOWN" << std::endl;
289  return false;
290  }
291 
292  void CarlaSSCameraPublisher::SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t* data) {
293  std::vector<uint8_t> vector_data;
294  const size_t size = height * width * 4;
295  vector_data.resize(size);
296  std::memcpy(&vector_data[0], &data[0], size);
297  SetData(seconds, nanoseconds, height, width, std::move(vector_data));
298  }
299 
300  void CarlaSSCameraPublisher::SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify) {
302  roi.x_offset(x_offset);
303  roi.y_offset(y_offset);
304  roi.height(height);
305  roi.width(width);
306  roi.do_rectify(do_rectify);
307  _impl_info->_info.roi(roi);
308  }
309 
310  void CarlaSSCameraPublisher::SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data) {
312  time.sec(seconds);
313  time.nanosec(nanoseconds);
314 
315  std_msgs::msg::Header header;
316  header.stamp(std::move(time));
317  header.frame_id(_frame_id);
318 
319  _impl->_image.header(std::move(header));
320  _impl->_image.width(width);
321  _impl->_image.height(height);
322  _impl->_image.encoding("bgra8"); //taken from the list of strings in include/sensor_msgs/image_encodings.h
323  _impl->_image.is_bigendian(0);
324  _impl->_image.step(_impl->_image.width() * sizeof(uint8_t) * 4);
325  _impl->_image.data(std::move(data)); //https://github.com/eProsima/Fast-DDS/issues/2330
326  }
327 
328  void CarlaSSCameraPublisher::SetCameraInfoData(int32_t seconds, uint32_t nanoseconds) {
330  time.sec(seconds);
331  time.nanosec(nanoseconds);
332 
333  std_msgs::msg::Header header;
334  header.stamp(std::move(time));
335  header.frame_id(_frame_id);
336  _impl_info->_info.header(header);
337  }
338 
339  CarlaSSCameraPublisher::CarlaSSCameraPublisher(const char* ros_name, const char* parent) :
340  _impl(std::make_shared<CarlaSSCameraPublisherImpl>()),
341  _impl_info(std::make_shared<CarlaCameraInfoPublisherImpl>()) {
342  _name = ros_name;
343  _parent = parent;
344  }
345 
347  if (!_impl)
348  return;
349 
350  if (_impl->_datawriter)
351  _impl->_publisher->delete_datawriter(_impl->_datawriter);
352 
353  if (_impl->_publisher)
354  _impl->_participant->delete_publisher(_impl->_publisher);
355 
356  if (_impl->_topic)
357  _impl->_participant->delete_topic(_impl->_topic);
358 
359  if (_impl->_participant)
360  efd::DomainParticipantFactory::get_instance()->delete_participant(_impl->_participant);
361 
362  if (!_impl_info)
363  return;
364 
365  if (_impl_info->_datawriter)
366  _impl_info->_publisher->delete_datawriter(_impl_info->_datawriter);
367 
368  if (_impl_info->_publisher)
369  _impl_info->_participant->delete_publisher(_impl_info->_publisher);
370 
371  if (_impl_info->_topic)
372  _impl_info->_participant->delete_topic(_impl_info->_topic);
373 
374  if (_impl_info->_participant)
375  efd::DomainParticipantFactory::get_instance()->delete_participant(_impl_info->_participant);
376  }
377 
379  _frame_id = other._frame_id;
380  _name = other._name;
381  _parent = other._parent;
382  _impl = other._impl;
383  _impl_info = other._impl_info;
384  }
385 
387  _frame_id = other._frame_id;
388  _name = other._name;
389  _parent = other._parent;
390  _impl = other._impl;
391  _impl_info = other._impl_info;
392 
393  return *this;
394  }
395 
397  _frame_id = std::move(other._frame_id);
398  _name = std::move(other._name);
399  _parent = std::move(other._parent);
400  _impl = std::move(other._impl);
401  _impl_info = std::move(other._impl_info);
402  }
403 
405  _frame_id = std::move(other._frame_id);
406  _name = std::move(other._name);
407  _parent = std::move(other._parent);
408  _impl = std::move(other._impl);
409  _impl_info = std::move(other._impl_info);
410 
411  return *this;
412  }
413 }
414 }
std::shared_ptr< CarlaSSCameraPublisherImpl > _impl
CarlaSSCameraPublisher & operator=(const CarlaSSCameraPublisher &)
void SetInfoRegionOfInterest(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify)
void SetCameraInfoData(int32_t seconds, uint32_t nanoseconds)
eprosima::fastrtps::rtps::InstanceHandle_t InstanceHandle_t
eprosima::fastrtps::types::ReturnCode_t erc
This file contains definitions of common data structures used in traffic manager. ...
Definition: Carla.cpp:133
This class represents the structure Header defined by the user in the IDL file.
Definition: Header.h:72
This class represents the structure CameraInfo defined by the user in the IDL file.
Definition: CameraInfo.h:73
This class represents the structure Image defined by the user in the IDL file.
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 width(uint32_t _width)
This function sets a value in member width.
This class represents the TopicDataType of the type Image defined by the user in the IDL file...
void InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
eProsima_user_DllExport void x_offset(uint32_t _x_offset)
This function sets a value in member x_offset.
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
eProsima_user_DllExport void sec(int32_t _sec)
This function sets a value in member sec.
Definition: Time.cpp:133
This class represents the TopicDataType of the type CameraInfo 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
This class represents the structure RegionOfInterest defined by the user in the IDL file...
const std::string & parent() const
This class represents the structure Time defined by the user in the IDL file.
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const uint8_t *data)
eProsima_user_DllExport void height(uint32_t _height)
This function sets a value in member height.
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_user_DllExport void y_offset(uint32_t _y_offset)
This function sets a value in member y_offset.
CarlaSSCameraPublisher(const char *ros_name="", const char *parent="")
void SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector< uint8_t > &&data)
eProsima_user_DllExport void do_rectify(bool _do_rectify)
This function sets a value in member do_rectify.