thermal_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 openSocket(int &m_socket_descriptor, sockaddr_in &m_socket, std::string &m_address, int m_udp_port)
60 {
61  if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
62  {
63  perror("Opening socket");
64  return false;
65  }
66  // else ROS_INFO("Socket created");
67 
68  memset((char *)&m_socket, 0, sizeof(struct sockaddr_in));
69  m_socket.sin_addr.s_addr = inet_addr((char *)m_address.c_str());
70  m_socket.sin_family = AF_INET;
71  m_socket.sin_port = htons(m_udp_port);
72 
73  if (inet_aton((char *)m_address.c_str(), &m_socket.sin_addr) == 0)
74  {
75  perror("inet_aton() failed");
76  return false;
77  }
78 
79  if (bind(m_socket_descriptor, (struct sockaddr *)&m_socket, sizeof(struct sockaddr_in)) == -1)
80  {
81  perror("Could not bind name to socket");
82  close(m_socket_descriptor);
83  return false;
84  }
85 
86  int rcvbufsize = 134217728;
87  if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (char *)&rcvbufsize, sizeof(rcvbufsize)))
88  {
89  perror("Error setting size to socket");
90  return false;
91  }
92 
93  // 1 second timeout for socket
94  struct timeval read_timeout;
95  read_timeout.tv_sec = 1;
96  setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVTIMEO, &read_timeout, sizeof read_timeout);
97 
98  return true;
99 }
100 
102 {
103  struct sockaddr_in m_socket;
104  int m_socket_descriptor; // Socket descriptor
105  std::string m_address = "0.0.0.0"; // Local address of the network interface port connected to the L3CAM
106  int m_udp_port = 6030; // For Thermal it's 6030
107 
108  socklen_t socket_len = sizeof(m_socket);
109  char *buffer;
110  buffer = (char *)malloc(64000);
111 
112  uint16_t m_image_height;
113  uint16_t m_image_width;
114  uint8_t m_image_channels;
115  uint32_t m_timestamp;
116  int m_image_data_size;
117  bool m_is_reading_image = false;
118  char *m_image_buffer = NULL;
119  int bytes_count = 0;
120 
121  if (!openSocket(m_socket_descriptor, m_socket, m_address, m_udp_port))
122  {
123  return;
124  }
125 
126  g_listening = true;
127  ROS_INFO("Thermal streaming");
128 
129  uint8_t *image_pointer = NULL;
130 
131  while (g_listening)
132  {
133  int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (struct sockaddr *)&m_socket, &socket_len);
134  if (size_read == 11) // Header
135  {
136  memcpy(&m_image_height, &buffer[1], 2);
137  memcpy(&m_image_width, &buffer[3], 2);
138  memcpy(&m_image_channels, &buffer[5], 1);
139 
140  if (image_pointer != NULL)
141  {
142  free(image_pointer);
143  image_pointer = NULL;
144  }
145  if (m_image_buffer != NULL)
146  {
147  free(m_image_buffer);
148  m_image_buffer = NULL;
149  }
150 
151  m_image_buffer = (char *)malloc(m_image_height * m_image_width * m_image_channels);
152  image_pointer = (uint8_t *)malloc(m_image_height * m_image_width * m_image_channels);
153 
154  memcpy(&m_timestamp, &buffer[6], sizeof(uint32_t));
155  m_image_data_size = m_image_height * m_image_width * m_image_channels;
156  m_is_reading_image = true;
157  bytes_count = 0;
158  }
159  else if (size_read == 1 && bytes_count == m_image_data_size) // End, send image
160  {
161  m_is_reading_image = false;
162  bytes_count = 0;
163  memcpy(image_pointer, m_image_buffer, m_image_data_size);
164 
165  cv::Mat img_data;
166  if (m_image_channels == 1)
167  {
168  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC1, image_pointer);
169  }
170  else if (m_image_channels == 3)
171  {
172  img_data = cv::Mat(m_image_height, m_image_width, CV_8UC3, image_pointer);
173  }
174 
175  std_msgs::Header header;
176  header.frame_id = "thermal";
177  // m_timestamp format: hhmmsszzz
178  time_t raw_time = ros::Time::now().toSec();
179  std::tm *time_info = std::localtime(&raw_time);
180  time_info->tm_sec = 0;
181  time_info->tm_min = 0;
182  time_info->tm_hour = 0;
183  header.stamp.sec = std::mktime(time_info) +
184  (uint32_t)(m_timestamp / 10000000) * 3600 + // hh
185  (uint32_t)((m_timestamp / 100000) % 100) * 60 + // mm
186  (uint32_t)((m_timestamp / 1000) % 100); // ss
187  header.stamp.nsec = (m_timestamp % 1000) * 1e6; // zzz
188 
189  const std::string encoding = m_image_channels == 1 ? sensor_msgs::image_encodings::MONO8 : sensor_msgs::image_encodings::BGR8;
190  sensor_msgs::ImagePtr img_msg = cv_bridge::CvImage(header, encoding, img_data).toImageMsg();
191 
192  publisher.publish(img_msg);
193  }
194  else if (size_read > 0 && m_is_reading_image) // Data
195  {
196  memcpy(&m_image_buffer[bytes_count], buffer, size_read);
197  bytes_count += size_read;
198 
199  // check if under size
200  if (bytes_count >= m_image_data_size)
201  m_is_reading_image = false;
202  }
203  // size_read == -1 --> timeout
204  }
205 
206  publisher.shutdown();
207  ROS_INFO_STREAM("Exiting thermal streaming thread");
208  free(buffer);
209 
210  shutdown(m_socket_descriptor, SHUT_RDWR);
211  close(m_socket_descriptor);
212 
213  pthread_exit(0);
214 }
215 
217 {
218  struct sockaddr_in m_socket;
219  int m_socket_descriptor; // Socket descriptor
220  std::string m_address = "0.0.0.0"; // Local address of the network interface port connected to the L3CAM
221  int m_udp_port = 6031; // For float Thermal it's 6031
222 
223  socklen_t socket_len = sizeof(m_socket);
224  char *buffer;
225  buffer = (char *)malloc(64000);
226 
227  uint16_t m_image_height;
228  uint16_t m_image_width;
229  uint32_t m_timestamp;
230  int m_image_data_size;
231  bool m_is_reading_image = false;
232  int bytes_count = 0;
233 
234  if (!openSocket(m_socket_descriptor, m_socket, m_address, m_udp_port))
235  {
236  return;
237  }
238 
239  g_listening = true;
240  ROS_INFO("Float Thermal streaming");
241 
242  float *thermal_data_pointer = NULL;
243  int float_pointer_cnt = 0;
244 
245  while (g_listening)
246  {
247  int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (struct sockaddr *)&m_socket, &socket_len);
248  if (size_read == 9) // Header
249  {
250  memcpy(&m_image_height, &buffer[1], 2);
251  memcpy(&m_image_width, &buffer[3], 2);
252  memcpy(&m_timestamp, &buffer[5], 4);
253 
254  if (thermal_data_pointer != NULL)
255  {
256  free(thermal_data_pointer);
257  thermal_data_pointer = NULL;
258  }
259 
260  m_image_data_size = m_image_height * m_image_width * sizeof(float);
261 
262  thermal_data_pointer = (float *)malloc(m_image_data_size);
263 
264  m_is_reading_image = true;
265  bytes_count = 0;
266  float_pointer_cnt = 0;
267  }
268  else if (size_read == 1) // End, send image
269  {
270  if(bytes_count != m_image_data_size)
271  {
272  ROS_WARN_STREAM("thermal NET PROBLEM: bytes_count != m_image_data_size");
273  continue;
274  }
275 
276  m_is_reading_image = false;
277  bytes_count = 0;
278  float_pointer_cnt = 0;
279 
280  cv::Mat float_image = cv::Mat(m_image_height, m_image_width, CV_32FC1, thermal_data_pointer);
281 
282  // publish float image
283  std_msgs::Header header;
284  header.frame_id = "f_thermal";
285  // m_timestamp format: hhmmsszzz
286  time_t raw_time = ros::Time::now().toSec();
287  std::tm *time_info = std::localtime(&raw_time);
288  time_info->tm_sec = 0;
289  time_info->tm_min = 0;
290  time_info->tm_hour = 0;
291  header.stamp.sec = std::mktime(time_info) +
292  (uint32_t)(m_timestamp / 10000000) * 3600 + // hh
293  (uint32_t)((m_timestamp / 100000) % 100) * 60 + // mm
294  (uint32_t)((m_timestamp / 1000) % 100); // ss
295  header.stamp.nsec = (m_timestamp % 1000) * 1e6; // zzz
296 
297  sensor_msgs::ImagePtr img_msg = cv_bridge::CvImage(header, sensor_msgs::image_encodings::TYPE_32FC1, float_image).toImageMsg();
298 
299  publisher.publish(img_msg);
300  }
301  else if (size_read > 0 && m_is_reading_image) // Data
302  {
303  memcpy(&thermal_data_pointer[float_pointer_cnt], buffer, size_read);
304  bytes_count += size_read;
305  float_pointer_cnt += size_read / 4;
306  }
307  // size_read == -1 --> timeout
308  }
309 
310  publisher.shutdown();
311  ROS_INFO_STREAM("Exiting float thermal streaming thread");
312  free(buffer);
313 
314  shutdown(m_socket_descriptor, SHUT_RDWR);
315  close(m_socket_descriptor);
316 
317  pthread_exit(0);
318 }
319 
320 namespace l3cam_ros
321 {
323  {
324  public:
326  {
327  declareServiceServers("thermal");
328  }
329 
332 
333  private:
335  {
336  g_listening = false;
337  }
338 
339  }; // class ThermalStream
340 
341 } // namespace l3cam_ros
342 
343 int main(int argc, char **argv)
344 {
345  ros::init(argc, argv, "thermal_stream");
346 
348 
349  // Check if service is available
350  ros::Duration timeout_duration(node->timeout_secs_);
351  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
352  {
353  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
355  }
356 
357  int error = L3CAM_OK;
358  bool sensor_is_available = false;
359  // Shutdown if sensor is not available or if error returned
360  if (node->client_get_sensors_.call(node->srv_get_sensors_))
361  {
362  error = node->srv_get_sensors_.response.error;
363 
364  if (!error)
365  {
366  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
367  {
368  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_thermal && node->srv_get_sensors_.response.sensors[i].sensor_available)
369  {
370  sensor_is_available = true;
371  }
372  }
373  }
374  else
375  {
376  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability in " << __func__ << ": " << getErrorDescription(error));
377  return error;
378  }
379  }
380  else
381  {
382  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
384  }
385 
386  if (sensor_is_available)
387  {
388  ROS_INFO_STREAM("Thermal camera available for streaming");
389  }
390  else
391  {
392  return 0;
393  }
394 
396  node->publisher_ = it.advertise("/img_thermal", 10);
397  std::thread thread(ImageThread, node->publisher_);
398  thread.detach();
399  node->f_publisher_ = node->advertise<sensor_msgs::Image>("/img_f_thermal", 10);
400  std::thread thread_f(FloatImageThread, node->f_publisher_);
401  thread_f.detach();
402 
403  node->spin();
404 
405  node->publisher_.shutdown();
406  node->f_publisher_.shutdown();
407  g_listening = false;
408  usleep(2000000);
409 
410  ros::shutdown();
411  return 0;
412 }
l3cam_ros::SensorStream
Definition: sensor_stream.hpp:38
l3cam_ros::ThermalStream::ThermalStream
ThermalStream()
Definition: thermal_stream.cpp:325
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
ros::Publisher
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)
g_listening
bool g_listening
Definition: thermal_stream.cpp:57
TimeBase< Time, Duration >::toSec
double toSec() const
ros::shutdown
ROSCPP_DECL void shutdown()
l3cam_ros::ThermalStream::stopListening
void stopListening()
Definition: thermal_stream.cpp:334
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
openSocket
bool openSocket(int &m_socket_descriptor, sockaddr_in &m_socket, std::string &m_address, int m_udp_port)
Definition: thermal_stream.cpp:59
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
l3cam_ros
Definition: l3cam_ros_node.hpp:133
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
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)
ImageThread
void ImageThread(image_transport::Publisher publisher)
Definition: thermal_stream.cpp:101
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
shutdown
ROSCONSOLE_DECL void shutdown()
l3cam_ros::ThermalStream
Definition: thermal_stream.cpp:322
ros::Publisher::shutdown
void shutdown()
l3cam_ros::SensorStream::declareServiceServers
void declareServiceServers(const std::string &sensor)
Definition: sensor_stream.cpp:51
image_transport::Publisher::shutdown
void shutdown()
main
int main(int argc, char **argv)
Definition: thermal_stream.cpp:343
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
image_transport.h
sensor_stream.hpp
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
FloatImageThread
void FloatImageThread(ros::Publisher publisher)
Definition: thermal_stream.cpp:216
sensor_msgs::image_encodings::TYPE_32FC1
const std::string TYPE_32FC1
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
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
header
const std::string header
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::shutdown
void shutdown()
ros::Duration
l3cam_ros::ThermalStream::f_publisher_
ros::Publisher f_publisher_
Definition: thermal_stream.cpp:331
l3cam_ros::ThermalStream::publisher_
image_transport::Publisher publisher_
Definition: thermal_stream.cpp:330
l3cam_ros::L3Cam::spin
void spin()
Definition: l3cam_ros_node.cpp:60
ros::Time::now
static Time now()


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