30 #include <sys/socket.h>
31 #include <netinet/in.h>
35 #include <arpa/inet.h>
37 #include <arpa/inet.h>
38 #include <sys/socket.h>
44 #include <sensor_msgs/Image.h>
50 #include <opencv2/imgproc/imgproc.hpp>
51 #include <opencv2/highgui/highgui.hpp>
54 #include <beamagine.h>
55 #include <beamErrors.h>
59 bool openSocket(
int &m_socket_descriptor, sockaddr_in &m_socket, std::string &m_address,
int m_udp_port)
61 if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
63 perror(
"Opening socket");
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);
73 if (inet_aton((
char *)m_address.c_str(), &m_socket.sin_addr) == 0)
75 perror(
"inet_aton() failed");
79 if (bind(m_socket_descriptor, (
struct sockaddr *)&m_socket,
sizeof(
struct sockaddr_in)) == -1)
81 perror(
"Could not bind name to socket");
82 close(m_socket_descriptor);
86 int rcvbufsize = 134217728;
87 if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (
char *)&rcvbufsize,
sizeof(rcvbufsize)))
89 perror(
"Error setting size to 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);
103 struct sockaddr_in m_socket;
104 int m_socket_descriptor;
105 std::string m_address =
"0.0.0.0";
106 int m_udp_port = 6030;
108 socklen_t socket_len =
sizeof(m_socket);
110 buffer = (
char *)malloc(64000);
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;
121 if (!
openSocket(m_socket_descriptor, m_socket, m_address, m_udp_port))
129 uint8_t *image_pointer = NULL;
133 int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (
struct sockaddr *)&m_socket, &socket_len);
136 memcpy(&m_image_height, &buffer[1], 2);
137 memcpy(&m_image_width, &buffer[3], 2);
138 memcpy(&m_image_channels, &buffer[5], 1);
140 if (image_pointer != NULL)
143 image_pointer = NULL;
145 if (m_image_buffer != NULL)
147 free(m_image_buffer);
148 m_image_buffer = NULL;
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);
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;
159 else if (size_read == 1 && bytes_count == m_image_data_size)
161 m_is_reading_image =
false;
163 memcpy(image_pointer, m_image_buffer, m_image_data_size);
166 if (m_image_channels == 1)
168 img_data = cv::Mat(m_image_height, m_image_width, CV_8UC1, image_pointer);
170 else if (m_image_channels == 3)
172 img_data = cv::Mat(m_image_height, m_image_width, CV_8UC3, image_pointer);
176 header.frame_id =
"thermal";
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 +
185 (uint32_t)((m_timestamp / 100000) % 100) * 60 +
186 (uint32_t)((m_timestamp / 1000) % 100);
187 header.stamp.nsec = (m_timestamp % 1000) * 1e6;
194 else if (size_read > 0 && m_is_reading_image)
196 memcpy(&m_image_buffer[bytes_count], buffer, size_read);
197 bytes_count += size_read;
200 if (bytes_count >= m_image_data_size)
201 m_is_reading_image =
false;
210 shutdown(m_socket_descriptor, SHUT_RDWR);
211 close(m_socket_descriptor);
218 struct sockaddr_in m_socket;
219 int m_socket_descriptor;
220 std::string m_address =
"0.0.0.0";
221 int m_udp_port = 6031;
223 socklen_t socket_len =
sizeof(m_socket);
225 buffer = (
char *)malloc(64000);
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;
234 if (!
openSocket(m_socket_descriptor, m_socket, m_address, m_udp_port))
240 ROS_INFO(
"Float Thermal streaming");
242 float *thermal_data_pointer = NULL;
243 int float_pointer_cnt = 0;
247 int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (
struct sockaddr *)&m_socket, &socket_len);
250 memcpy(&m_image_height, &buffer[1], 2);
251 memcpy(&m_image_width, &buffer[3], 2);
252 memcpy(&m_timestamp, &buffer[5], 4);
254 if (thermal_data_pointer != NULL)
256 free(thermal_data_pointer);
257 thermal_data_pointer = NULL;
260 m_image_data_size = m_image_height * m_image_width *
sizeof(float);
262 thermal_data_pointer = (
float *)malloc(m_image_data_size);
264 m_is_reading_image =
true;
266 float_pointer_cnt = 0;
268 else if (size_read == 1)
270 if(bytes_count != m_image_data_size)
272 ROS_WARN_STREAM(
"thermal NET PROBLEM: bytes_count != m_image_data_size");
276 m_is_reading_image =
false;
278 float_pointer_cnt = 0;
280 cv::Mat float_image = cv::Mat(m_image_height, m_image_width, CV_32FC1, thermal_data_pointer);
284 header.frame_id =
"f_thermal";
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 +
293 (uint32_t)((m_timestamp / 100000) % 100) * 60 +
294 (uint32_t)((m_timestamp / 1000) % 100);
295 header.stamp.nsec = (m_timestamp % 1000) * 1e6;
301 else if (size_read > 0 && m_is_reading_image)
303 memcpy(&thermal_data_pointer[float_pointer_cnt], buffer, size_read);
304 bytes_count += size_read;
305 float_pointer_cnt += size_read / 4;
314 shutdown(m_socket_descriptor, SHUT_RDWR);
315 close(m_socket_descriptor);
343 int main(
int argc,
char **argv)
351 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
357 int error = L3CAM_OK;
358 bool sensor_is_available =
false;
360 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
362 error =
node->srv_get_sensors_.response.error;
366 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
368 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_thermal &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
370 sensor_is_available =
true;
386 if (sensor_is_available)