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/PointCloud2.h"
45 #include <sensor_msgs/PointField.h>
49 #include <beamagine.h>
50 #include <beamErrors.h>
56 struct sockaddr_in m_socket;
57 int m_socket_descriptor;
58 std::string m_address =
"0.0.0.0";
59 int m_udp_port = 6050;
61 socklen_t socket_len =
sizeof(m_socket);
63 buffer = (
char *)malloc(64000);
65 int32_t m_pointcloud_size;
66 int32_t *m_pointcloud_data;
68 bool m_is_reading_pointcloud =
false;
69 int points_received = 1;
70 int pointcloud_index = 1;
72 if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
74 perror(
"Opening socket");
79 memset((
char *)&m_socket, 0,
sizeof(
struct sockaddr_in));
80 m_socket.sin_addr.s_addr = inet_addr((
char *)m_address.c_str());
81 m_socket.sin_family = AF_INET;
82 m_socket.sin_port = htons(m_udp_port);
84 if (inet_aton((
char *)m_address.c_str(), &m_socket.sin_addr) == 0)
86 perror(
"inet_aton() failed");
90 if (bind(m_socket_descriptor, (
struct sockaddr *)&m_socket,
sizeof(
struct sockaddr_in)) == -1)
92 perror(
"Could not bind name to socket");
93 close(m_socket_descriptor);
97 int rcvbufsize = 134217728;
98 if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (
char *)&rcvbufsize,
sizeof(rcvbufsize)))
100 perror(
"Error setting size to socket");
105 struct timeval read_timeout;
106 read_timeout.tv_sec = 1;
107 setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVTIMEO, &read_timeout,
sizeof read_timeout);
114 int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (
struct sockaddr *)&m_socket, &socket_len);
118 memcpy(&m_pointcloud_size, &buffer[1], 4);
119 m_pointcloud_data = (int32_t *)malloc(
sizeof(int32_t) * (((m_pointcloud_size) * 5) + 1));
120 memcpy(&m_pointcloud_data[0], &m_pointcloud_size,
sizeof(int32_t));
121 int32_t suma_1, suma_2;
122 memcpy(&suma_1, &buffer[5],
sizeof(int32_t));
123 memcpy(&suma_2, &buffer[9],
sizeof(int32_t));
124 memcpy(&m_timestamp, &buffer[13],
sizeof(uint32_t));
125 m_is_reading_pointcloud =
true;
127 pointcloud_index = 1;
129 else if (size_read == 1)
131 if(points_received != m_pointcloud_size)
133 ROS_WARN(
"lidar NET PROBLEM: points_received != m_pointcloud_size");
137 m_is_reading_pointcloud =
false;
138 int32_t *data_received = (int32_t *)malloc(
sizeof(int32_t) * (m_pointcloud_size * 5) + 1);
139 memcpy(&data_received[0], &m_pointcloud_data[0],
sizeof(int32_t) * ((m_pointcloud_size * 5) + 1));
141 int size_pc = data_received[0];
143 sensor_msgs::PointCloud2 pcl_msg;
146 pcl_msg.header = std_msgs::Header();
147 pcl_msg.header.frame_id =
"lidar";
150 std::tm *time_info = std::localtime(&raw_time);
151 time_info->tm_sec = 0;
152 time_info->tm_min = 0;
153 time_info->tm_hour = 0;
154 pcl_msg.header.stamp.sec = std::mktime(time_info) +
155 (uint32_t)(m_timestamp / 10000000) * 3600 +
156 (uint32_t)((m_timestamp / 100000) % 100) * 60 +
157 (uint32_t)((m_timestamp / 1000) % 100);
158 pcl_msg.header.stamp.nsec = (m_timestamp % 1000) * 1e6;
161 pcl_msg.width = size_pc;
162 pcl_msg.is_dense =
true;
165 pcl_msg.point_step =
sizeof(float) * 3 +
sizeof(uint16_t) +
sizeof(uint32_t);
166 pcl_msg.row_step = pcl_msg.point_step * pcl_msg.width;
167 pcl_msg.data.resize(pcl_msg.row_step);
172 "x", 1, sensor_msgs::PointField::FLOAT32,
173 "y", 1, sensor_msgs::PointField::FLOAT32,
174 "z", 1, sensor_msgs::PointField::FLOAT32,
175 "intensity", 1, sensor_msgs::PointField::UINT16,
176 "rgb", 1, sensor_msgs::PointField::UINT32);
185 for (
int i = 0; i < size_pc; ++i)
187 *iter_y = -(float)data_received[5 * i + 1] / 1000.0;
189 *iter_z = -(float)data_received[5 * i + 2] / 1000.0;
191 *iter_x = (float)data_received[5 * i + 3] / 1000.0;
193 *iter_intensity = (uint16_t)data_received[5 * i + 4];
195 *iter_rgb = (uint32_t)data_received[5 * i + 5];
206 free(m_pointcloud_data);
208 pointcloud_index = 1;
210 else if (size_read > 0 && m_is_reading_pointcloud)
213 memcpy(&points, &buffer[0], 4);
214 memcpy(&m_pointcloud_data[pointcloud_index], &buffer[4], (
sizeof(int32_t) * (points * 5)));
216 pointcloud_index += (points * 5);
218 points_received += points;
228 ROS_INFO(
"Exiting lidar streaming thread");
230 free(m_pointcloud_data);
232 shutdown(m_socket_descriptor, SHUT_RDWR);
233 close(m_socket_descriptor);
260 int main(
int argc,
char **argv)
268 if (!
node->client_get_sensors_.waitForExistence(timeout_duration))
274 int error = L3CAM_OK;
275 bool sensor_is_available =
false;
277 if (
node->client_get_sensors_.call(
node->srv_get_sensors_))
279 error =
node->srv_get_sensors_.response.error;
283 for (
int i = 0; i <
node->srv_get_sensors_.response.num_sensors; ++i)
285 if (
node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_lidar &&
node->srv_get_sensors_.response.sensors[i].sensor_available)
287 sensor_is_available =
true;
303 if (sensor_is_available)
305 ROS_INFO(
"LiDAR available for streaming");