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>
64 struct sockaddr_in m_socket;
65 int m_socket_descriptor;
66 std::string m_address =
"0.0.0.0";
67 int m_udp_port = 6020;
69 socklen_t socket_len =
sizeof(m_socket);
71 buffer = (
char *)malloc(64000);
73 uint16_t m_image_height;
74 uint16_t m_image_width;
75 uint8_t m_image_channels;
77 int m_image_data_size;
78 bool m_is_reading_image =
false;
79 char *m_image_buffer = NULL;
82 if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
84 perror(
"Opening socket");
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);
94 if (inet_aton((
char *)m_address.c_str(), &m_socket.sin_addr) == 0)
96 perror(
"inet_aton() failed");
100 if (bind(m_socket_descriptor, (
struct sockaddr *)&m_socket,
sizeof(
struct sockaddr_in)) == -1)
102 perror(
"Could not bind name to socket");
103 close(m_socket_descriptor);
107 int rcvbufsize = 134217728;
108 if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (
char *)&rcvbufsize,
sizeof(rcvbufsize)))
110 perror(
"Error setting size to 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);
123 ROS_INFO(
"Allied Narrow streaming");
125 uint8_t *image_pointer = NULL;
129 int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (
struct sockaddr *)&m_socket, &socket_len);
132 memcpy(&m_image_height, &buffer[1], 2);
133 memcpy(&m_image_width, &buffer[3], 2);
134 memcpy(&m_image_channels, &buffer[5], 1);
136 if (image_pointer != NULL)
139 image_pointer = NULL;
141 if (m_image_buffer != NULL)
143 free(m_image_buffer);
144 m_image_buffer = NULL;
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);
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;
155 else if (size_read == 1)
157 if(bytes_count != m_image_data_size)
159 ROS_WARN_STREAM(
"rgb_narrow NET PROBLEM: bytes_count != m_image_data_size");
163 m_is_reading_image =
false;
165 memcpy(image_pointer, m_image_buffer, m_image_data_size);
168 if (m_image_channels == 1)
170 img_data = cv::Mat(m_image_height, m_image_width, CV_8UC1, image_pointer);
172 else if (m_image_channels == 2)
174 img_data = cv::Mat(m_image_height, m_image_width, CV_8UC2, image_pointer);
177 cv::cvtColor(img_data, img_data, cv::COLOR_YUV2BGR_YUYV);
181 cv::cvtColor(img_data, img_data, cv::COLOR_YUV2BGR_Y422);
184 else if (m_image_channels == 3)
186 img_data = cv::Mat(m_image_height, m_image_width, CV_8UC3, image_pointer);
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 +
199 (uint32_t)((m_timestamp / 100000) % 100) * 60 +
200 (uint32_t)((m_timestamp / 1000) % 100);
201 header.stamp.nsec = (m_timestamp % 1000) * 1e6;
208 else if (size_read > 0 && m_is_reading_image)
210 memcpy(&m_image_buffer[bytes_count], buffer, size_read);
211 bytes_count += size_read;
223 free(m_image_buffer);
225 shutdown(m_socket_descriptor, SHUT_RDWR);
226 close(m_socket_descriptor);
252 int main(
int argc,
char **argv)
254 ros::init(argc, argv,
"rgb_narrow_stream");
260 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
266 int error = L3CAM_OK;
267 bool sensor_is_available =
false;
269 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
271 error =
node->srv_get_sensors_.response.error;
275 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
277 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_econ_rgb &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
279 sensor_is_available =
true;
283 else if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_econ_wide &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
285 sensor_is_available =
true;
289 else if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_allied_narrow &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
291 sensor_is_available =
true;
308 if (sensor_is_available)
311 node->declareServiceServers((
g_rgb ?
"rgb" :
"allied_narrow"));