polarimetric_wide_stream.cpp
Go to the documentation of this file.
1 /* Copyright (c) 2023, Beamagine
2 
3  All rights reserved.
4 
5  Redistribution and use in source and binary forms, with or without modification,
6  are permitted provided that the following conditions are met:
7 
8  - Redistributions of source code must retain the above copyright notice,
9  this list of conditions and the following disclaimer.
10  - Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation and/or
12  other materials provided with the distribution.
13  - Neither the name of copyright holders nor the names of its contributors may be
14  used to endorse or promote products derived from this software without specific
15  prior written permission.
16 
17  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS “AS IS” AND ANY
18  EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
19  MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
20  COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL,
21  EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22  SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
23  HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR
24  TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
25  EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "sensor_stream.hpp"
29 
30 #include <sys/socket.h>
31 #include <netinet/in.h>
32 #include <netdb.h>
33 #include <stdio.h>
34 #include <string.h>
35 #include <arpa/inet.h>
36 #include <stdint.h>
37 #include <arpa/inet.h>
38 #include <sys/socket.h>
39 #include <unistd.h>
40 
41 #include <pthread.h>
42 #include <thread>
43 
44 #include <sensor_msgs/Image.h>
48 
49 #include <cv_bridge/cv_bridge.h>
50 #include <opencv2/imgproc/imgproc.hpp>
51 #include <opencv2/highgui/highgui.hpp>
52 
53 #include <libL3Cam.h>
54 #include <beamagine.h>
55 #include <beamErrors.h>
56 
57 #include "l3cam_ros/EnablePolarimetricCameraStreamProcessedImage.h"
58 #include "l3cam_ros/ChangePolarimetricCameraProcessType.h"
59 
61 
62 bool g_listening = false;
63 
64 bool g_pol = false; // true if polarimetric available, false if wide available
65 bool g_stream_processed = true;
66 
67 cv::Mat rgbpol2rgb(const cv::Mat img, polAngle angle = no_angle)
68 {
69  /*
70  0 1 2 3
71  +-------+-------+-------+-------+ 0
72  | 90° | 45° | 90° | 45° |
73  | B | B | Gb | Gb |
74  +-------+-------+-------+-------+ 1
75  | 135° | 0° | 135° | 0° |
76  | B | B | Gb | Gb |
77  +-------+-------+-------+-------+ 2
78  | 90° | 45° | 90° | 45° |
79  | Gr | Gr | R | R |
80  +-------+-------+-------+-------+ 3
81  | 135° | 0° | 135° | 0° |
82  | Gr | Gr | R | R |
83  +-------+-------+-------+-------+
84  */
85 
86  cv::Mat bayer(img.rows / 2, img.cols / 2, CV_8UC1, cv::Scalar(0));
87  cv::Mat rgb;
88 
89  auto is_valid_pixel = [](int px_y, int px_x, polAngle angle) -> bool {
90  switch (angle)
91  {
92  case angle_0: return (px_y == 1 || px_y == 3) && (px_x == 1 || px_x == 3);
93  case angle_45: return (px_y == 0 || px_y == 2) && (px_x == 1 || px_x == 3);
94  case angle_90: return (px_y == 0 || px_y == 2) && (px_x == 0 || px_x == 2);
95  case angle_135: return (px_y == 1 || px_y == 3) && (px_x == 0 || px_x == 2);
96  default: return false;
97  }
98  };
99 
100  if (angle != no_angle)
101  {
102  for (int y = 0; y < img.rows; ++y)
103  {
104  for (int x = 0; x < img.cols; ++x)
105  {
106  const int px_y = y % 4;
107  const int px_x = x % 4;
108 
109  if (is_valid_pixel(px_y, px_x, angle))
110  {
111  bayer.at<uint8_t>(y / 2, x / 2) = img.at<uint8_t>(y, x);
112  }
113  }
114  }
115  cv::cvtColor(bayer, rgb, cv::COLOR_BayerRG2BGR);
116  }
117  else
118  {
119  cv::Mat bayer0 = cv::Mat::zeros(img.rows / 2, img.cols / 2, CV_8UC1);
120  cv::Mat bayer90 = cv::Mat::zeros(img.rows / 2, img.cols / 2, CV_8UC1);
121 
122  for (int y = 0; y < img.rows; ++y)
123  {
124  for (int x = 0; x < img.cols; ++x)
125  {
126  const int px_y = y % 4;
127  const int px_x = x % 4;
128 
129  if ((px_y == 1 || px_y == 3) && (px_x == 1 || px_x == 3))
130  {
131  bayer0.at<uint8_t>(y / 2, x / 2) = img.at<uint8_t>(y, x);
132  }
133  if ((px_y == 0 || px_y == 2) && (px_x == 0 || px_x == 2))
134  {
135  bayer90.at<uint8_t>(y / 2, x / 2) = img.at<uint8_t>(y, x);
136  }
137  }
138  }
139 
140  cv::Mat rgb0, rgb90;
141  cv::cvtColor(bayer0, rgb0, cv::COLOR_BayerRG2BGR);
142  cv::cvtColor(bayer90, rgb90, cv::COLOR_BayerRG2BGR);
143  rgb = rgb0 / 2 + rgb90 / 2;
144  }
145 
146  return rgb;
147 }
148 
150 {
151  struct sockaddr_in m_socket;
152  int m_socket_descriptor; // Socket descriptor
153  std::string m_address = "0.0.0.0"; // Local address of the network interface port connected to the L3CAM
154  int m_udp_port = 6060; // For Polarimetric and Allied Wide it's 6060
155 
156  socklen_t socket_len = sizeof(m_socket);
157  char *buffer;
158  buffer = (char *)malloc(64000);
159 
160  uint16_t m_image_height;
161  uint16_t m_image_width;
162  uint8_t m_image_channels;
163  uint32_t m_timestamp;
164  int m_image_data_size;
165  bool m_is_reading_image = false;
166  char *m_image_buffer = NULL;
167  int bytes_count = 0;
168 
169  if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
170  {
171  perror("Opening socket");
172  return;
173  }
174  // else ROS_INFO("Socket Polarimetric created");
175 
176  memset((char *)&m_socket, 0, sizeof(struct sockaddr_in));
177  m_socket.sin_addr.s_addr = inet_addr((char *)m_address.c_str());
178  m_socket.sin_family = AF_INET;
179  m_socket.sin_port = htons(m_udp_port);
180 
181  if (inet_aton((char *)m_address.c_str(), &m_socket.sin_addr) == 0)
182  {
183  perror("inet_aton() failed");
184  return;
185  }
186 
187  if (bind(m_socket_descriptor, (struct sockaddr *)&m_socket, sizeof(struct sockaddr_in)) == -1)
188  {
189  perror("Could not bind name to socket");
190  close(m_socket_descriptor);
191  return;
192  }
193 
194  int rcvbufsize = 134217728;
195  if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (char *)&rcvbufsize, sizeof(rcvbufsize)))
196  {
197  perror("Error setting size to socket");
198  return;
199  }
200 
201  // 1 second timeout for socket
202  struct timeval read_timeout;
203  read_timeout.tv_sec = 1;
204  setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVTIMEO, &read_timeout, sizeof read_timeout);
205 
206  g_listening = true;
207  if (g_pol)
208  ROS_INFO("Polarimetric streaming");
209  else
210  ROS_INFO("Allied Wide streaming");
211 
212  uint8_t *image_pointer = NULL;
213 
214  while (g_listening)
215  {
216  int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (struct sockaddr *)&m_socket, &socket_len);
217  if (size_read == 11) // Header
218  {
219  memcpy(&m_image_height, &buffer[1], 2);
220  memcpy(&m_image_width, &buffer[3], 2);
221  memcpy(&m_image_channels, &buffer[5], 1);
222 
223  if (image_pointer != NULL)
224  {
225  free(image_pointer);
226  image_pointer = NULL;
227  }
228  if (m_image_buffer != NULL)
229  {
230  free(m_image_buffer);
231  m_image_buffer = NULL;
232  }
233 
234  m_image_buffer = (char *)malloc(m_image_height * m_image_width * m_image_channels);
235  image_pointer = (uint8_t *)malloc(m_image_height * m_image_width * m_image_channels);
236 
237  memcpy(&m_timestamp, &buffer[6], sizeof(uint32_t));
238  m_image_data_size = m_image_height * m_image_width * m_image_channels;
239  m_is_reading_image = true;
240  bytes_count = 0;
241  }
242  else if (size_read == 1) // End, send image
243  {
244  if(bytes_count != m_image_data_size)
245  {
246  ROS_WARN_STREAM("pol_wide NET PROBLEM: bytes_count != m_image_data_size");
247  continue;
248  }
249 
250  m_is_reading_image = false;
251  bytes_count = 0;
252  memcpy(image_pointer, m_image_buffer, m_image_data_size);
253 
254  cv::Mat img_data;
255  if (m_image_channels == 1)
256  {
257  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC1, image_pointer);
258  }
259  else if (m_image_channels == 2)
260  {
261  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC2, image_pointer);
262  cv::cvtColor(img_data, img_data, cv::COLOR_YUV2BGR_Y422);
263  }
264  else if (m_image_channels == 3)
265  {
266  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC3, image_pointer);
267  }
268 
269  std_msgs::Header header;
270  header.frame_id = g_pol ? "polarimetric" : "allied_wide";
271  // m_timestamp format: hhmmsszzz
272  time_t raw_time = ros::Time::now().toSec();
273  std::tm *time_info = std::localtime(&raw_time);
274  time_info->tm_sec = 0;
275  time_info->tm_min = 0;
276  time_info->tm_hour = 0;
277  header.stamp.sec = std::mktime(time_info) +
278  (uint32_t)(m_timestamp / 10000000) * 3600 + // hh
279  (uint32_t)((m_timestamp / 100000) % 100) * 60 + // mm
280  (uint32_t)((m_timestamp / 1000) % 100); // ss
281  header.stamp.nsec = (m_timestamp % 1000) * 1e6; // zzz
282 
283  const std::string encoding = m_image_channels == 1 ? sensor_msgs::image_encodings::MONO8 : sensor_msgs::image_encodings::BGR8;
284  sensor_msgs::ImagePtr img_msg = cv_bridge::CvImage(header, encoding, img_data).toImageMsg();
285 
286  publisher.publish(img_msg);
287 
288  if(!extra_publisher.getTopic().empty() && g_stream_processed)
289  {
290  cv::Mat img_processed = rgbpol2rgb(img_data, (polAngle)g_angle);
291 
292  std_msgs::Header header_processed = header;
293  header.frame_id = "polarimetric_processed";
294 
295  sensor_msgs::ImagePtr img_processed_msg = cv_bridge::CvImage(header_processed, sensor_msgs::image_encodings::BGR8, img_processed).toImageMsg();
296  extra_publisher.publish(img_processed_msg);
297  }
298  }
299  else if (size_read > 0 && m_is_reading_image) // Data
300  {
301  memcpy(&m_image_buffer[bytes_count], buffer, size_read);
302  bytes_count += size_read;
303 
304  // check if under size
305  //if (bytes_count >= m_image_data_size)
306  // m_is_reading_image = false;
307  }
308  // size_read == -1 --> timeout
309  }
310 
311  publisher.shutdown();
312  extra_publisher.shutdown();
313 
314  ROS_INFO_STREAM("Exiting " << (g_pol ? "Polarimetric" : "Allied Wide") << " streaming thread");
315  free(buffer);
316  free(m_image_buffer);
317 
318  shutdown(m_socket_descriptor, SHUT_RDWR);
319  close(m_socket_descriptor);
320 }
321 
322 namespace l3cam_ros
323 {
325  {
326  public:
328  {
329  loadParam("polarimetric_stream_processed_image", g_stream_processed, true);
330  loadParam("polarimetric_process_type", g_angle, 127);
331  }
332 
334  {
335  srv_stream_processed_ = this->advertiseService("enable_polarimetric_stream_processed_image", &PolarimetricWideStream::enableStreamProcessed, this);
336  srv_process_type_ = this->advertiseService("change_polarimetric_process_type", &PolarimetricWideStream::changeProcessType, this);
337  }
338 
340 
341  private:
342  template <typename T>
343  void loadParam(const std::string &param_name, T &param_var, const T &default_val)
344  {
345  std::string full_param_name;
346 
347  if (searchParam(param_name, full_param_name))
348  {
349  if(!getParam(full_param_name, param_var))
350  {
351  ROS_ERROR_STREAM(this->getNamespace() << " error: Could not retreive '" << full_param_name << "' param value");
352  }
353  }
354  else
355  {
356  ROS_WARN_STREAM(this->getNamespace() << " Parameter '" << param_name << "' not defined");
357  param_var = default_val;
358  }
359  }
360 
362  {
363  g_listening = false;
364  }
365 
366  bool enableStreamProcessed(l3cam_ros::EnablePolarimetricCameraStreamProcessedImage::Request &req, l3cam_ros::EnablePolarimetricCameraStreamProcessedImage::Response &res)
367  {
368  g_stream_processed = req.enabled;
369  res.error = 0;
370 
371  return true;
372  }
373 
374  bool changeProcessType(l3cam_ros::ChangePolarimetricCameraProcessType::Request &req, l3cam_ros::ChangePolarimetricCameraProcessType::Response &res)
375  {
376  if(req.type < 0 || req.type > no_angle)
377  {
378  res.error = L3CAM_ROS_INVALID_POLARIMETRIC_PROCESS_TYPE;
379  return true;
380  }
381 
382  g_angle = req.type;
383  res.error = 0;
384 
385  return true;
386  }
387 
390 
391  }; // class PolarimetricWideStream
392 
393 } // namespace l3cam_ros
394 
395 int main(int argc, char **argv)
396 {
397  ros::init(argc, argv, "polarimetric_wide_stream");
398 
400 
401  // Check if service is available
402  ros::Duration timeout_duration(node->timeout_secs_);
403  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
404  {
405  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
407  }
408 
409  int error = L3CAM_OK;
410  bool sensor_is_available = false;
411  // Shutdown if sensor is not available or if error returned
412  if (node->client_get_sensors_.call(node->srv_get_sensors_))
413  {
414  error = node->srv_get_sensors_.response.error;
415 
416  if (!error)
417  {
418  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
419  {
420  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_pol && node->srv_get_sensors_.response.sensors[i].sensor_available)
421  {
422  sensor_is_available = true;
423  g_pol = true;
424  }
425  else if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_allied_wide && node->srv_get_sensors_.response.sensors[i].sensor_available)
426  {
427  sensor_is_available = true;
428  g_pol = false;
429  }
430  }
431  }
432  else
433  {
434  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability in " << __func__ << ": " << getErrorDescription(error));
435  return error;
436  }
437  }
438  else
439  {
440  ROS_ERROR_STREAM(node->getNamespace() << "_error: Failed to call service get_sensors_available");
442  }
443 
444  if (sensor_is_available)
445  {
446  ROS_INFO_STREAM((g_pol ? "Polarimetric" : "Allied Wide") << " camera available for streaming");
447  node->declareServiceServers(g_pol ? "polarimetric" : "allied_wide");
448  if(g_pol) node->declareExtraService();
449  }
450  else
451  {
452  return 0;
453  }
454 
456  node->publisher_ = it.advertise(g_pol ? "/img_polarimetric" : "/img_wide", 10);
457  if(g_pol)
458  {
459  node->extra_publisher_ = it.advertise("/img_polarimetric_processed", 10);
460  }
461  std::thread thread(ImageThread, node->publisher_, node->extra_publisher_);
462  thread.detach();
463 
464  node->spin();
465 
466  node->publisher_.shutdown();
467  node->extra_publisher_.shutdown();
468  g_listening = false;
469  usleep(2000000);
470 
471  ros::shutdown();
472  return 0;
473 }
l3cam_ros::SensorStream
Definition: sensor_stream.hpp:38
image_transport::Publisher::getTopic
std::string getTopic() const
l3cam_ros::PolarimetricWideStream::changeProcessType
bool changeProcessType(l3cam_ros::ChangePolarimetricCameraProcessType::Request &req, l3cam_ros::ChangePolarimetricCameraProcessType::Response &res)
Definition: polarimetric_wide_stream.cpp:374
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
image_encodings.h
image_transport::ImageTransport
ImageThread
void ImageThread(image_transport::Publisher publisher, image_transport::Publisher extra_publisher)
Definition: polarimetric_wide_stream.cpp:149
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
angle_0
@ angle_0
Definition: l3cam_ros_utils.hpp:47
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
angle_90
@ angle_90
Definition: l3cam_ros_utils.hpp:49
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
l3cam_ros::PolarimetricWideStream::declareExtraService
void declareExtraService()
Definition: polarimetric_wide_stream.cpp:333
main
int main(int argc, char **argv)
Definition: polarimetric_wide_stream.cpp:395
TimeBase< Time, Duration >::toSec
double toSec() const
ros::shutdown
ROSCPP_DECL void shutdown()
ros::NodeHandle::advertiseService
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros
Definition: l3cam_ros_node.hpp:133
l3cam_ros::PolarimetricWideStream::PolarimetricWideStream
PolarimetricWideStream()
Definition: polarimetric_wide_stream.cpp:327
l3cam_ros::PolarimetricWideStream::srv_stream_processed_
ros::ServiceServer srv_stream_processed_
Definition: polarimetric_wide_stream.cpp:388
l3cam_ros::L3Cam::timeout_secs_
int timeout_secs_
Definition: l3cam_ros_node.hpp:404
image_transport::ImageTransport::advertise
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
shutdown
ROSCONSOLE_DECL void shutdown()
l3cam_ros::PolarimetricWideStream
Definition: polarimetric_wide_stream.cpp:324
g_stream_processed
bool g_stream_processed
Definition: polarimetric_wide_stream.cpp:65
ros::NodeHandle::searchParam
bool searchParam(const std::string &key, std::string &result) const
l3cam_ros::PolarimetricWideStream::srv_process_type_
ros::ServiceServer srv_process_type_
Definition: polarimetric_wide_stream.cpp:389
g_listening
bool g_listening
Definition: polarimetric_wide_stream.cpp:62
image_transport::Publisher::shutdown
void shutdown()
l3cam_ros::PolarimetricWideStream::stopListening
void stopListening()
Definition: polarimetric_wide_stream.cpp:361
g_angle
int g_angle
Definition: polarimetric_wide_stream.cpp:60
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
no_angle
@ no_angle
Definition: l3cam_ros_utils.hpp:51
image_transport.h
sensor_stream.hpp
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
image_transport::Publisher
sensor_msgs::image_encodings::MONO8
const std::string MONO8
polAngle
polAngle
Definition: l3cam_ros_utils.hpp:45
cv_bridge.h
angle_135
@ angle_135
Definition: l3cam_ros_utils.hpp:50
l3cam_ros::PolarimetricWideStream::loadParam
void loadParam(const std::string &param_name, T &param_var, const T &default_val)
Definition: polarimetric_wide_stream.cpp:343
rgbpol2rgb
cv::Mat rgbpol2rgb(const cv::Mat img, polAngle angle=no_angle)
Definition: polarimetric_wide_stream.cpp:67
cv_bridge::CvImage
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
l3cam_ros::PolarimetricWideStream::publisher_
image_transport::Publisher publisher_
Definition: polarimetric_wide_stream.cpp:339
l3cam_ros::PolarimetricWideStream::extra_publisher_
image_transport::Publisher extra_publisher_
Definition: polarimetric_wide_stream.cpp:339
sensor_msgs::image_encodings::BGR8
const std::string BGR8
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
header
const std::string header
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::shutdown
void shutdown()
angle_45
@ angle_45
Definition: l3cam_ros_utils.hpp:48
ros::Duration
l3cam_ros::PolarimetricWideStream::enableStreamProcessed
bool enableStreamProcessed(l3cam_ros::EnablePolarimetricCameraStreamProcessedImage::Request &req, l3cam_ros::EnablePolarimetricCameraStreamProcessedImage::Response &res)
Definition: polarimetric_wide_stream.cpp:366
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
ros::Time::now
static Time now()
g_pol
bool g_pol
Definition: polarimetric_wide_stream.cpp:64


l3cam_ros
Author(s): Beamagine
autogenerated on Wed May 28 2025 02:53:15