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>
57 #include "l3cam_ros/EnablePolarimetricCameraStreamProcessedImage.h"
58 #include "l3cam_ros/ChangePolarimetricCameraProcessType.h"
86 cv::Mat bayer(img.rows / 2, img.cols / 2, CV_8UC1, cv::Scalar(0));
89 auto is_valid_pixel = [](
int px_y,
int px_x,
polAngle angle) ->
bool {
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;
102 for (
int y = 0; y < img.rows; ++y)
104 for (
int x = 0; x < img.cols; ++x)
106 const int px_y = y % 4;
107 const int px_x = x % 4;
109 if (is_valid_pixel(px_y, px_x, angle))
111 bayer.at<uint8_t>(y / 2, x / 2) = img.at<uint8_t>(y, x);
115 cv::cvtColor(bayer, rgb, cv::COLOR_BayerRG2BGR);
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);
122 for (
int y = 0; y < img.rows; ++y)
124 for (
int x = 0; x < img.cols; ++x)
126 const int px_y = y % 4;
127 const int px_x = x % 4;
129 if ((px_y == 1 || px_y == 3) && (px_x == 1 || px_x == 3))
131 bayer0.at<uint8_t>(y / 2, x / 2) = img.at<uint8_t>(y, x);
133 if ((px_y == 0 || px_y == 2) && (px_x == 0 || px_x == 2))
135 bayer90.at<uint8_t>(y / 2, x / 2) = img.at<uint8_t>(y, x);
141 cv::cvtColor(bayer0, rgb0, cv::COLOR_BayerRG2BGR);
142 cv::cvtColor(bayer90, rgb90, cv::COLOR_BayerRG2BGR);
143 rgb = rgb0 / 2 + rgb90 / 2;
151 struct sockaddr_in m_socket;
152 int m_socket_descriptor;
153 std::string m_address =
"0.0.0.0";
154 int m_udp_port = 6060;
156 socklen_t socket_len =
sizeof(m_socket);
158 buffer = (
char *)malloc(64000);
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;
169 if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
171 perror(
"Opening socket");
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);
181 if (inet_aton((
char *)m_address.c_str(), &m_socket.sin_addr) == 0)
183 perror(
"inet_aton() failed");
187 if (bind(m_socket_descriptor, (
struct sockaddr *)&m_socket,
sizeof(
struct sockaddr_in)) == -1)
189 perror(
"Could not bind name to socket");
190 close(m_socket_descriptor);
194 int rcvbufsize = 134217728;
195 if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (
char *)&rcvbufsize,
sizeof(rcvbufsize)))
197 perror(
"Error setting size to 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);
212 uint8_t *image_pointer = NULL;
216 int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (
struct sockaddr *)&m_socket, &socket_len);
219 memcpy(&m_image_height, &buffer[1], 2);
220 memcpy(&m_image_width, &buffer[3], 2);
221 memcpy(&m_image_channels, &buffer[5], 1);
223 if (image_pointer != NULL)
226 image_pointer = NULL;
228 if (m_image_buffer != NULL)
230 free(m_image_buffer);
231 m_image_buffer = NULL;
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);
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;
242 else if (size_read == 1)
244 if(bytes_count != m_image_data_size)
246 ROS_WARN_STREAM(
"pol_wide NET PROBLEM: bytes_count != m_image_data_size");
250 m_is_reading_image =
false;
252 memcpy(image_pointer, m_image_buffer, m_image_data_size);
255 if (m_image_channels == 1)
257 img_data = cv::Mat(m_image_height, m_image_width, CV_8UC1, image_pointer);
259 else if (m_image_channels == 2)
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);
264 else if (m_image_channels == 3)
266 img_data = cv::Mat(m_image_height, m_image_width, CV_8UC3, image_pointer);
270 header.frame_id =
g_pol ?
"polarimetric" :
"allied_wide";
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 +
279 (uint32_t)((m_timestamp / 100000) % 100) * 60 +
280 (uint32_t)((m_timestamp / 1000) % 100);
281 header.stamp.nsec = (m_timestamp % 1000) * 1e6;
292 std_msgs::Header header_processed =
header;
293 header.frame_id =
"polarimetric_processed";
296 extra_publisher.
publish(img_processed_msg);
299 else if (size_read > 0 && m_is_reading_image)
301 memcpy(&m_image_buffer[bytes_count], buffer, size_read);
302 bytes_count += size_read;
316 free(m_image_buffer);
318 shutdown(m_socket_descriptor, SHUT_RDWR);
319 close(m_socket_descriptor);
342 template <
typename T>
343 void loadParam(
const std::string ¶m_name, T ¶m_var,
const T &default_val)
345 std::string full_param_name;
349 if(!
getParam(full_param_name, param_var))
357 param_var = default_val;
366 bool enableStreamProcessed(l3cam_ros::EnablePolarimetricCameraStreamProcessedImage::Request &req, l3cam_ros::EnablePolarimetricCameraStreamProcessedImage::Response &res)
374 bool changeProcessType(l3cam_ros::ChangePolarimetricCameraProcessType::Request &req, l3cam_ros::ChangePolarimetricCameraProcessType::Response &res)
376 if(req.type < 0 || req.type >
no_angle)
378 res.error = L3CAM_ROS_INVALID_POLARIMETRIC_PROCESS_TYPE;
395 int main(
int argc,
char **argv)
397 ros::init(argc, argv,
"polarimetric_wide_stream");
403 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
409 int error = L3CAM_OK;
410 bool sensor_is_available =
false;
412 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
414 error =
node->srv_get_sensors_.response.error;
418 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
420 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_pol &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
422 sensor_is_available =
true;
425 else if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_allied_wide &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
427 sensor_is_available =
true;
444 if (sensor_is_available)
447 node->declareServiceServers(
g_pol ?
"polarimetric" :
"allied_wide");
459 node->extra_publisher_ = it.
advertise(
"/img_polarimetric_processed", 10);