rgb_narrow_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 bool g_listening = false;
58 
59 bool g_rgb = false; // true if rgb available, false if narrow available
60 bool g_wide = false;
61 
63 {
64  struct sockaddr_in m_socket;
65  int m_socket_descriptor; // Socket descriptor
66  std::string m_address = "0.0.0.0"; // Local address of the network interface port connected to the L3CAM
67  int m_udp_port = 6020; // For RGB and Allied Narrow it's 6020
68 
69  socklen_t socket_len = sizeof(m_socket);
70  char *buffer;
71  buffer = (char *)malloc(64000);
72 
73  uint16_t m_image_height;
74  uint16_t m_image_width;
75  uint8_t m_image_channels;
76  uint32_t m_timestamp;
77  int m_image_data_size;
78  bool m_is_reading_image = false;
79  char *m_image_buffer = NULL;
80  int bytes_count = 0;
81 
82  if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
83  {
84  perror("Opening socket");
85  return;
86  }
87  // else ROS_INFO("Socket RGB created");
88 
89  memset((char *)&m_socket, 0, sizeof(struct sockaddr_in));
90  m_socket.sin_addr.s_addr = inet_addr((char *)m_address.c_str());
91  m_socket.sin_family = AF_INET;
92  m_socket.sin_port = htons(m_udp_port);
93 
94  if (inet_aton((char *)m_address.c_str(), &m_socket.sin_addr) == 0)
95  {
96  perror("inet_aton() failed");
97  return;
98  }
99 
100  if (bind(m_socket_descriptor, (struct sockaddr *)&m_socket, sizeof(struct sockaddr_in)) == -1)
101  {
102  perror("Could not bind name to socket");
103  close(m_socket_descriptor);
104  return;
105  }
106 
107  int rcvbufsize = 134217728;
108  if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (char *)&rcvbufsize, sizeof(rcvbufsize)))
109  {
110  perror("Error setting size to socket");
111  return;
112  }
113 
114  // 1 second timeout for socket
115  struct timeval read_timeout;
116  read_timeout.tv_sec = 1;
117  setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVTIMEO, &read_timeout, sizeof read_timeout);
118 
119  g_listening = true;
120  if (g_rgb)
121  ROS_INFO("RGB streaming");
122  else
123  ROS_INFO("Allied Narrow streaming");
124 
125  uint8_t *image_pointer = NULL;
126 
127  while (g_listening)
128  {
129  int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (struct sockaddr *)&m_socket, &socket_len);
130  if (size_read == 11) // Header
131  {
132  memcpy(&m_image_height, &buffer[1], 2);
133  memcpy(&m_image_width, &buffer[3], 2);
134  memcpy(&m_image_channels, &buffer[5], 1);
135 
136  if (image_pointer != NULL)
137  {
138  free(image_pointer);
139  image_pointer = NULL;
140  }
141  if (m_image_buffer != NULL)
142  {
143  free(m_image_buffer);
144  m_image_buffer = NULL;
145  }
146 
147  m_image_buffer = (char *)malloc(m_image_height * m_image_width * m_image_channels);
148  image_pointer = (uint8_t *)malloc(m_image_height * m_image_width * m_image_channels);
149 
150  memcpy(&m_timestamp, &buffer[6], sizeof(uint32_t));
151  m_image_data_size = m_image_height * m_image_width * m_image_channels;
152  m_is_reading_image = true;
153  bytes_count = 0;
154  }
155  else if (size_read == 1) // End, send image
156  {
157  if(bytes_count != m_image_data_size)
158  {
159  ROS_WARN_STREAM("rgb_narrow NET PROBLEM: bytes_count != m_image_data_size");
160  continue;
161  }
162 
163  m_is_reading_image = false;
164  bytes_count = 0;
165  memcpy(image_pointer, m_image_buffer, m_image_data_size);
166 
167  cv::Mat img_data;
168  if (m_image_channels == 1)
169  {
170  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC1, image_pointer);
171  }
172  else if (m_image_channels == 2)
173  {
174  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC2, image_pointer);
175  if(g_rgb && !g_wide) // econ
176  {
177  cv::cvtColor(img_data, img_data, cv::COLOR_YUV2BGR_YUYV);
178  }
179  else // econ wide and narrow
180  {
181  cv::cvtColor(img_data, img_data, cv::COLOR_YUV2BGR_Y422);
182  }
183  }
184  else if (m_image_channels == 3)
185  {
186  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC3, image_pointer);
187  }
188 
189  std_msgs::Header header;
190  header.frame_id = g_rgb ? "rgb" : "allied_narrow";
191  // m_timestamp format: hhmmsszzz
192  time_t raw_time = ros::Time::now().toSec();
193  std::tm *time_info = std::localtime(&raw_time);
194  time_info->tm_sec = 0;
195  time_info->tm_min = 0;
196  time_info->tm_hour = 0;
197  header.stamp.sec = std::mktime(time_info) +
198  (uint32_t)(m_timestamp / 10000000) * 3600 + // hh
199  (uint32_t)((m_timestamp / 100000) % 100) * 60 + // mm
200  (uint32_t)((m_timestamp / 1000) % 100); // ss
201  header.stamp.nsec = (m_timestamp % 1000) * 1e6; // zzz
202 
203  const std::string encoding = m_image_channels == 1 ? sensor_msgs::image_encodings::MONO8 : sensor_msgs::image_encodings::BGR8;
204  sensor_msgs::ImagePtr img_msg = cv_bridge::CvImage(header, encoding, img_data).toImageMsg();
205 
206  publisher.publish(img_msg);
207  }
208  else if (size_read > 0 && m_is_reading_image) // Data
209  {
210  memcpy(&m_image_buffer[bytes_count], buffer, size_read);
211  bytes_count += size_read;
212 
213  // check if under size
214  //if (bytes_count >= m_image_data_size)
215  // m_is_reading_image = false;
216  }
217  // size_read == -1 --> timeout
218  }
219 
220  publisher.shutdown();
221  ROS_INFO_STREAM("Exiting " << (g_rgb ? "RGB" : "Allied Narrow") << " streaming thread");
222  free(buffer);
223  free(m_image_buffer);
224 
225  shutdown(m_socket_descriptor, SHUT_RDWR);
226  close(m_socket_descriptor);
227 
228  pthread_exit(0);
229 }
230 
231 namespace l3cam_ros
232 {
234  {
235  public:
237  {
238  }
239 
241 
242  private:
244  {
245  g_listening = false;
246  }
247 
248  }; // class RgbNarrowStream
249 
250 } // namespace l3cam_ros
251 
252 int main(int argc, char **argv)
253 {
254  ros::init(argc, argv, "rgb_narrow_stream");
255 
257 
258  // Check if service is available
259  ros::Duration timeout_duration(node->timeout_secs_);
260  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
261  {
262  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
264  }
265 
266  int error = L3CAM_OK;
267  bool sensor_is_available = false;
268  // Shutdown if sensor is not available or if error returned
269  if (node->client_get_sensors_.call(node->srv_get_sensors_))
270  {
271  error = node->srv_get_sensors_.response.error;
272 
273  if (!error)
274  {
275  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
276  {
277  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_econ_rgb && node->srv_get_sensors_.response.sensors[i].sensor_available)
278  {
279  sensor_is_available = true;
280  g_rgb = true;
281  g_wide = false;
282  }
283  else if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_econ_wide && node->srv_get_sensors_.response.sensors[i].sensor_available)
284  {
285  sensor_is_available = true;
286  g_rgb = true;
287  g_wide = true;
288  }
289  else if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_allied_narrow && node->srv_get_sensors_.response.sensors[i].sensor_available)
290  {
291  sensor_is_available = true;
292  g_rgb = false;
293  }
294  }
295  }
296  else
297  {
298  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability in " << __func__ << ": " << getErrorDescription(error));
299  return error;
300  }
301  }
302  else
303  {
304  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
306  }
307 
308  if (sensor_is_available)
309  {
310  ROS_INFO_STREAM((g_rgb ? "RGB" : "Allied Narrow") << " camera available for streaming");
311  node->declareServiceServers((g_rgb ? "rgb" : "allied_narrow"));
312  }
313  else
314  {
315  return 0;
316  }
317 
319  node->publisher_ = it.advertise(g_rgb ? "/img_rgb" : "/img_narrow", 10);
320  std::thread thread(ImageThread, node->publisher_);
321  thread.detach();
322 
323  node->spin();
324 
325  node->publisher_.shutdown();
326  g_listening = false;
327  usleep(2000000);
328 
329  ros::shutdown();
330  return 0;
331 }
l3cam_ros::SensorStream
Definition: sensor_stream.hpp:38
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
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
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)
l3cam_ros::RgbNarrowStream
Definition: rgb_narrow_stream.cpp:233
TimeBase< Time, Duration >::toSec
double toSec() const
ros::shutdown
ROSCPP_DECL void shutdown()
g_wide
bool g_wide
Definition: rgb_narrow_stream.cpp:60
ImageThread
void ImageThread(image_transport::Publisher publisher)
Definition: rgb_narrow_stream.cpp:62
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::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_WARN_STREAM
#define ROS_WARN_STREAM(args)
shutdown
ROSCONSOLE_DECL void shutdown()
g_rgb
bool g_rgb
Definition: rgb_narrow_stream.cpp:59
image_transport::Publisher::shutdown
void shutdown()
l3cam_ros::RgbNarrowStream::RgbNarrowStream
RgbNarrowStream()
Definition: rgb_narrow_stream.cpp:236
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
image_transport.h
l3cam_ros::RgbNarrowStream::stopListening
void stopListening()
Definition: rgb_narrow_stream.cpp:243
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
cv_bridge.h
cv_bridge::CvImage
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
sensor_msgs::image_encodings::BGR8
const std::string BGR8
l3cam_ros::RgbNarrowStream::publisher_
image_transport::Publisher publisher_
Definition: rgb_narrow_stream.cpp:240
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
main
int main(int argc, char **argv)
Definition: rgb_narrow_stream.cpp:252
header
const std::string header
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::shutdown
void shutdown()
ros::Duration
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
g_listening
bool g_listening
Definition: rgb_narrow_stream.cpp:57
ros::Time::now
static Time now()


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