CARLA
 
载入中...
搜索中...
未找到
CarlaOpticalFlowCameraPublisher.cpp
浏览该文件的文档.
1#define _GLIBCXX_USE_CXX11_ABI 0
2
4
5#include <string>
6#include <cmath>
7
11
12#include <fastdds/dds/domain/DomainParticipant.hpp>
13#include <fastdds/dds/publisher/Publisher.hpp>
14#include <fastdds/dds/topic/Topic.hpp>
15#include <fastdds/dds/publisher/DataWriter.hpp>
16#include <fastdds/dds/topic/TypeSupport.hpp>
17
18#include <fastdds/dds/domain/qos/DomainParticipantQos.hpp>
19#include <fastdds/dds/domain/DomainParticipantFactory.hpp>
20#include <fastdds/dds/publisher/qos/PublisherQos.hpp>
21#include <fastdds/dds/topic/qos/TopicQos.hpp>
22
23#include <fastrtps/attributes/ParticipantAttributes.h>
24#include <fastrtps/qos/QosPolicies.h>
25#include <fastdds/dds/publisher/qos/DataWriterQos.hpp>
26#include <fastdds/dds/publisher/DataWriterListener.hpp>
27
28template <typename T> T CLAMP(const T& value, const T& low, const T& high)
29{
30 return value < low ? low : (value > high ? high : value);
31}
32
33namespace carla {
34namespace ros2 {
35
36 namespace efd = eprosima::fastdds::dds;
37 using erc = eprosima::fastrtps::types::ReturnCode_t;
39 efd::DomainParticipant* _participant { nullptr };
40 efd::Publisher* _publisher { nullptr };
41 efd::Topic* _topic { nullptr };
42 efd::DataWriter* _datawriter { nullptr };
43 efd::TypeSupport _type { new sensor_msgs::msg::ImagePubSubType() };
46 };
47
48 struct CarlaCameraInfoPublisherImpl {
49 efd::DomainParticipant* _participant { nullptr };
50 efd::Publisher* _publisher { nullptr };
51 efd::Topic* _topic { nullptr };
52 efd::DataWriter* _datawriter { nullptr };
53 efd::TypeSupport _type { new sensor_msgs::msg::CameraInfoPubSubType() };
54 CarlaListener _listener {};
55 bool _init { false};
57 };
58
62
63 void CarlaOpticalFlowCameraPublisher::InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify) {
64 _impl_info->_info = std::move(sensor_msgs::msg::CameraInfo(height, width, fov));
65 SetInfoRegionOfInterest(x_offset, y_offset, height, width, do_rectify);
66 _impl_info->_init = true;
67 }
68
72
74 if (_impl->_type == nullptr) {
75 std::cerr << "Invalid TypeSupport" << std::endl;
76 return false;
77 }
78
79 efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT;
80 pqos.name(_name);
81 auto factory = efd::DomainParticipantFactory::get_instance();
82 _impl->_participant = factory->create_participant(0, pqos);
83 if (_impl->_participant == nullptr) {
84 std::cerr << "Failed to create DomainParticipant" << std::endl;
85 return false;
86 }
87 _impl->_type.register_type(_impl->_participant);
88
89 efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT;
90 _impl->_publisher = _impl->_participant->create_publisher(pubqos, nullptr);
91 if (_impl->_publisher == nullptr) {
92 std::cerr << "Failed to create Publisher" << std::endl;
93 return false;
94 }
95
96 efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT;
97 const std::string publisher_type {"/image"};
98 const std::string base { "rt/carla/" };
99 std::string topic_name = base;
100 if (!_parent.empty())
101 topic_name += _parent + "/";
102 topic_name += _name;
103 topic_name += publisher_type;
104 _impl->_topic = _impl->_participant->create_topic(topic_name, _impl->_type->getName(), tqos);
105 if (_impl->_topic == nullptr) {
106 std::cerr << "Failed to create Topic" << std::endl;
107 return false;
108 }
109
110 efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT;
111 wqos.endpoint().history_memory_policy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
112 efd::DataWriterListener* listener = (efd::DataWriterListener*)_impl->_listener._impl.get();
113 _impl->_datawriter = _impl->_publisher->create_datawriter(_impl->_topic, wqos, listener);
114 if (_impl->_datawriter == nullptr) {
115 std::cerr << "Failed to create DataWriter" << std::endl;
116 return false;
117 }
119 return true;
120 }
121
123 if (_impl_info->_type == nullptr) {
124 std::cerr << "Invalid TypeSupport" << std::endl;
125 return false;
126 }
127
128 efd::DomainParticipantQos pqos = efd::PARTICIPANT_QOS_DEFAULT;
129 pqos.name(_name);
130 auto factory = efd::DomainParticipantFactory::get_instance();
131 _impl_info->_participant = factory->create_participant(0, pqos);
132 if (_impl_info->_participant == nullptr) {
133 std::cerr << "Failed to create DomainParticipant" << std::endl;
134 return false;
135 }
136 _impl_info->_type.register_type(_impl_info->_participant);
137
138 efd::PublisherQos pubqos = efd::PUBLISHER_QOS_DEFAULT;
139 _impl_info->_publisher = _impl_info->_participant->create_publisher(pubqos, nullptr);
140 if (_impl_info->_publisher == nullptr) {
141 std::cerr << "Failed to create Publisher" << std::endl;
142 return false;
143 }
144
145 efd::TopicQos tqos = efd::TOPIC_QOS_DEFAULT;
146 const std::string publisher_type {"/camera_info"};
147 const std::string base { "rt/carla/" };
148 std::string topic_name = base;
149 if (!_parent.empty())
150 topic_name += _parent + "/";
151 topic_name += _name;
152 topic_name += publisher_type;
153 _impl_info->_topic = _impl_info->_participant->create_topic(topic_name, _impl_info->_type->getName(), tqos);
154 if (_impl_info->_topic == nullptr) {
155 std::cerr << "Failed to create Topic" << std::endl;
156 return false;
157 }
158 efd::DataWriterQos wqos = efd::DATAWRITER_QOS_DEFAULT;
159 efd::DataWriterListener* listener = (efd::DataWriterListener*)_impl_info->_listener._impl.get();
160 _impl_info->_datawriter = _impl_info->_publisher->create_datawriter(_impl_info->_topic, wqos, listener);
161 if (_impl_info->_datawriter == nullptr) {
162 std::cerr << "Failed to create DataWriter" << std::endl;
163 return false;
164 }
165
167 return true;
168 }
169
173
175 eprosima::fastrtps::rtps::InstanceHandle_t instance_handle;
176 eprosima::fastrtps::types::ReturnCode_t rcode = _impl->_datawriter->write(&_impl->_image, instance_handle);
177 if (rcode == erc::ReturnCodeValue::RETCODE_OK) {
178 return true;
179 }
180 if (rcode == erc::ReturnCodeValue::RETCODE_ERROR) {
181 std::cerr << "RETCODE_ERROR" << std::endl;
182 return false;
183 }
184 if (rcode == erc::ReturnCodeValue::RETCODE_UNSUPPORTED) {
185 std::cerr << "RETCODE_UNSUPPORTED" << std::endl;
186 return false;
187 }
188 if (rcode == erc::ReturnCodeValue::RETCODE_BAD_PARAMETER) {
189 std::cerr << "RETCODE_BAD_PARAMETER" << std::endl;
190 return false;
191 }
192 if (rcode == erc::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET) {
193 std::cerr << "RETCODE_PRECONDITION_NOT_MET" << std::endl;
194 return false;
195 }
196 if (rcode == erc::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES) {
197 std::cerr << "RETCODE_OUT_OF_RESOURCES" << std::endl;
198 return false;
199 }
200 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ENABLED) {
201 std::cerr << "RETCODE_NOT_ENABLED" << std::endl;
202 return false;
203 }
204 if (rcode == erc::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY) {
205 std::cerr << "RETCODE_IMMUTABLE_POLICY" << std::endl;
206 return false;
207 }
208 if (rcode == erc::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY) {
209 std::cerr << "RETCODE_INCONSISTENT_POLICY" << std::endl;
210 return false;
211 }
212 if (rcode == erc::ReturnCodeValue::RETCODE_ALREADY_DELETED) {
213 std::cerr << "RETCODE_ALREADY_DELETED" << std::endl;
214 return false;
215 }
216 if (rcode == erc::ReturnCodeValue::RETCODE_TIMEOUT) {
217 std::cerr << "RETCODE_TIMEOUT" << std::endl;
218 return false;
219 }
220 if (rcode == erc::ReturnCodeValue::RETCODE_NO_DATA) {
221 std::cerr << "RETCODE_NO_DATA" << std::endl;
222 return false;
223 }
224 if (rcode == erc::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION) {
225 std::cerr << "RETCODE_ILLEGAL_OPERATION" << std::endl;
226 return false;
227 }
228 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY) {
229 std::cerr << "RETCODE_NOT_ALLOWED_BY_SECURITY" << std::endl;
230 return false;
231 }
232 std::cerr << "UNKNOWN" << std::endl;
233 return false;
234 }
235
237 eprosima::fastrtps::rtps::InstanceHandle_t instance_handle;
238 eprosima::fastrtps::types::ReturnCode_t rcode = _impl_info->_datawriter->write(&_impl_info->_info, instance_handle);
239 if (rcode == erc::ReturnCodeValue::RETCODE_OK) {
240 return true;
241 }
242 if (rcode == erc::ReturnCodeValue::RETCODE_ERROR) {
243 std::cerr << "RETCODE_ERROR" << std::endl;
244 return false;
245 }
246 if (rcode == erc::ReturnCodeValue::RETCODE_UNSUPPORTED) {
247 std::cerr << "RETCODE_UNSUPPORTED" << std::endl;
248 return false;
249 }
250 if (rcode == erc::ReturnCodeValue::RETCODE_BAD_PARAMETER) {
251 std::cerr << "RETCODE_BAD_PARAMETER" << std::endl;
252 return false;
253 }
254 if (rcode == erc::ReturnCodeValue::RETCODE_PRECONDITION_NOT_MET) {
255 std::cerr << "RETCODE_PRECONDITION_NOT_MET" << std::endl;
256 return false;
257 }
258 if (rcode == erc::ReturnCodeValue::RETCODE_OUT_OF_RESOURCES) {
259 std::cerr << "RETCODE_OUT_OF_RESOURCES" << std::endl;
260 return false;
261 }
262 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ENABLED) {
263 std::cerr << "RETCODE_NOT_ENABLED" << std::endl;
264 return false;
265 }
266 if (rcode == erc::ReturnCodeValue::RETCODE_IMMUTABLE_POLICY) {
267 std::cerr << "RETCODE_IMMUTABLE_POLICY" << std::endl;
268 return false;
269 }
270 if (rcode == erc::ReturnCodeValue::RETCODE_INCONSISTENT_POLICY) {
271 std::cerr << "RETCODE_INCONSISTENT_POLICY" << std::endl;
272 return false;
273 }
274 if (rcode == erc::ReturnCodeValue::RETCODE_ALREADY_DELETED) {
275 std::cerr << "RETCODE_ALREADY_DELETED" << std::endl;
276 return false;
277 }
278 if (rcode == erc::ReturnCodeValue::RETCODE_TIMEOUT) {
279 std::cerr << "RETCODE_TIMEOUT" << std::endl;
280 return false;
281 }
282 if (rcode == erc::ReturnCodeValue::RETCODE_NO_DATA) {
283 std::cerr << "RETCODE_NO_DATA" << std::endl;
284 return false;
285 }
286 if (rcode == erc::ReturnCodeValue::RETCODE_ILLEGAL_OPERATION) {
287 std::cerr << "RETCODE_ILLEGAL_OPERATION" << std::endl;
288 return false;
289 }
290 if (rcode == erc::ReturnCodeValue::RETCODE_NOT_ALLOWED_BY_SECURITY) {
291 std::cerr << "RETCODE_NOT_ALLOWED_BY_SECURITY" << std::endl;
292 return false;
293 }
294 std::cerr << "UNKNOWN" << std::endl;
295 return false;
296 }
297
298 void CarlaOpticalFlowCameraPublisher::SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const float* data) {
299 constexpr float pi = 3.1415f;
300 constexpr float rad2ang = 360.0f/(2.0f*pi);
301 const size_t max_index = width * height * 2;
302 std::vector<uint8_t> vector_data;
303 vector_data.resize(height * width * 4);
304 size_t data_index = 0;
305 for (size_t index = 0; index < max_index; index += 2) {
306 const float vx = data[index];
307 const float vy = data[index + 1];
308 float angle = 180.0f + std::atan2(vy, vx) * rad2ang;
309 if (angle < 0)
310 {
311 angle = 360.0f + angle;
312 }
313 angle = std::fmod(angle, 360.0f);
314
315 const float norm = std::sqrt(vx * vx + vy * vy);
316 const float shift = 0.999f;
317 const float a = 1.0f / std::log(0.1f + shift);
318 const float intensity = CLAMP<float>(a * std::log(norm + shift), 0.0f, 1.0f);
319
320 const float& H = angle;
321 const float S = 1.0f;
322 const float V = intensity;
323 const float H_60 = H * (1.0f / 60.0f);
324
325 const float C = V * S;
326 const float X = C * (1.0f - std::abs(std::fmod(H_60, 2.0f) - 1.0f));
327 const float m = V - C;
328
329 float r = 0;
330 float g = 0;
331 float b = 0;
332 const unsigned int angle_case = static_cast<const unsigned int>(H_60);
333 switch (angle_case) {
334 case 0:
335 r = C;
336 g = X;
337 b = 0;
338 break;
339 case 1:
340 r = X;
341 g = C;
342 b = 0;
343 break;
344 case 2:
345 r = 0;
346 g = C;
347 b = X;
348 break;
349 case 3:
350 r = 0;
351 g = X;
352 b = C;
353 break;
354 case 4:
355 r = X;
356 g = 0;
357 b = C;
358 break;
359 case 5:
360 r = C;
361 g = 0;
362 b = X;
363 break;
364 default:
365 r = 1;
366 g = 1;
367 b = 1;
368 break;
369 }
370
371 const uint8_t R = static_cast<uint8_t>((r + m) * 255.0f);
372 const uint8_t G = static_cast<uint8_t>((g + m) * 255.0f);
373 const uint8_t B = static_cast<uint8_t>((b + m) * 255.0f);
374
375 vector_data[data_index++] = B;
376 vector_data[data_index++] = G;
377 vector_data[data_index++] = R;
378 vector_data[data_index++] = 0;
379 }
380 SetData(seconds, nanoseconds, height, width, std::move(vector_data));
381 }
382
383 void CarlaOpticalFlowCameraPublisher::SetInfoRegionOfInterest( uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, bool do_rectify) {
385 roi.x_offset(x_offset);
386 roi.y_offset(y_offset);
387 roi.height(height);
388 roi.width(width);
389 roi.do_rectify(do_rectify);
390 _impl_info->_info.roi(roi);
391 }
392
393 void CarlaOpticalFlowCameraPublisher::SetData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, std::vector<uint8_t>&& data) {
395 time.sec(seconds);
396 time.nanosec(nanoseconds);
397
399 header.stamp(std::move(time));
400 header.frame_id(_frame_id);
401
402 _impl->_image.header(std::move(header));
403 _impl->_image.width(width);
404 _impl->_image.height(height);
405 _impl->_image.encoding("bgra8");
406 _impl->_image.is_bigendian(0);
407 _impl->_image.step(_impl->_image.width() * sizeof(uint8_t) * 4);
408 _impl->_image.data(std::move(data)); //https://github.com/eProsima/Fast-DDS/issues/2330
409 }
410
411 void CarlaOpticalFlowCameraPublisher::SetCameraInfoData(int32_t seconds, uint32_t nanoseconds) {
413 time.sec(seconds);
414 time.nanosec(nanoseconds);
415
417 header.stamp(std::move(time));
418 header.frame_id(_frame_id);
419 _impl_info->_info.header(header);
420 }
421
423 _impl(std::make_shared<CarlaOpticalFlowCameraPublisherImpl>()),
424 _impl_info(std::make_shared<CarlaCameraInfoPublisherImpl>()) {
425 _name = ros_name;
426 _parent = parent;
427 }
428
430 if (!_impl)
431 return;
432
433 if (_impl->_datawriter)
434 _impl->_publisher->delete_datawriter(_impl->_datawriter);
435
436 if (_impl->_publisher)
437 _impl->_participant->delete_publisher(_impl->_publisher);
438
439 if (_impl->_topic)
440 _impl->_participant->delete_topic(_impl->_topic);
441
442 if (_impl->_participant)
443 efd::DomainParticipantFactory::get_instance()->delete_participant(_impl->_participant);
444
445 if (!_impl_info)
446 return;
447
448 if (_impl_info->_datawriter)
449 _impl_info->_publisher->delete_datawriter(_impl_info->_datawriter);
450
451 if (_impl_info->_publisher)
452 _impl_info->_participant->delete_publisher(_impl_info->_publisher);
453
454 if (_impl_info->_topic)
455 _impl_info->_participant->delete_topic(_impl_info->_topic);
456
457 if (_impl_info->_participant)
458 efd::DomainParticipantFactory::get_instance()->delete_participant(_impl_info->_participant);
459 }
460
468
470 _frame_id = other._frame_id;
471 _name = other._name;
472 _parent = other._parent;
473 _impl = other._impl;
474 _impl_info = other._impl_info;
475
476 return *this;
477 }
478
480 _frame_id = std::move(other._frame_id);
481 _name = std::move(other._name);
482 _parent = std::move(other._parent);
483 _impl = std::move(other._impl);
484 _impl_info = std::move(other._impl_info);
485
486 }
487
489 _frame_id = std::move(other._frame_id);
490 _name = std::move(other._name);
491 _parent = std::move(other._parent);
492 _impl = std::move(other._impl);
493 _impl_info = std::move(other._impl_info);
494
495 return *this;
496 }
497}
498}
T CLAMP(const T &value, const T &low, const T &high)
carla::rpc::Response< T > R
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 InitInfoData(uint32_t x_offset, uint32_t y_offset, uint32_t height, uint32_t width, float fov, bool do_rectify)
CarlaOpticalFlowCameraPublisher & operator=(const CarlaOpticalFlowCameraPublisher &)
void SetImageData(int32_t seconds, uint32_t nanoseconds, size_t height, size_t width, const float *data)
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)
CarlaOpticalFlowCameraPublisher(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)
std::shared_ptr< CarlaOpticalFlowCameraPublisherImpl > _impl
std::shared_ptr< CarlaCameraInfoPublisherImpl > _impl_info
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 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