lidar_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/PointCloud2.h"
45 #include <sensor_msgs/PointField.h>
47 
48 #include <libL3Cam.h>
49 #include <beamagine.h>
50 #include <beamErrors.h>
51 
52 bool g_listening = false;
53 
55 {
56  struct sockaddr_in m_socket;
57  int m_socket_descriptor; // Socket descriptor
58  std::string m_address = "0.0.0.0"; // Local address of the network interface port connected to the L3CAM
59  int m_udp_port = 6050; // For the lidar it's 6050
60 
61  socklen_t socket_len = sizeof(m_socket);
62  char *buffer;
63  buffer = (char *)malloc(64000);
64 
65  int32_t m_pointcloud_size;
66  int32_t *m_pointcloud_data;
67  uint32_t m_timestamp;
68  bool m_is_reading_pointcloud = false;
69  int points_received = 1;
70  int pointcloud_index = 1;
71 
72  if ((m_socket_descriptor = socket(AF_INET, SOCK_DGRAM, IPPROTO_UDP)) == -1)
73  {
74  perror("Opening socket");
75  return;
76  }
77  // else ROS_INFO("Socket Lidar created");
78 
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);
83 
84  if (inet_aton((char *)m_address.c_str(), &m_socket.sin_addr) == 0)
85  {
86  perror("inet_aton() failed");
87  return;
88  }
89 
90  if (bind(m_socket_descriptor, (struct sockaddr *)&m_socket, sizeof(struct sockaddr_in)) == -1)
91  {
92  perror("Could not bind name to socket");
93  close(m_socket_descriptor);
94  return;
95  }
96 
97  int rcvbufsize = 134217728;
98  if (0 != setsockopt(m_socket_descriptor, SOL_SOCKET, SO_RCVBUF, (char *)&rcvbufsize, sizeof(rcvbufsize)))
99  {
100  perror("Error setting size to socket");
101  return;
102  }
103 
104  // 1 second timeout for 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);
108 
109  g_listening = true;
110  ROS_INFO("LiDAR streaming.");
111 
112  while (g_listening)
113  {
114  int size_read = recvfrom(m_socket_descriptor, buffer, 64000, 0, (struct sockaddr *)&m_socket, &socket_len);
115 
116  if (size_read == 17) // Header
117  {
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;
126  points_received = 0;
127  pointcloud_index = 1;
128  }
129  else if (size_read == 1) // End, send point cloud
130  {
131  if(points_received != m_pointcloud_size)
132  {
133  ROS_WARN("lidar NET PROBLEM: points_received != m_pointcloud_size");
134  continue;
135  }
136 
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));
140 
141  int size_pc = data_received[0];
142 
143  sensor_msgs::PointCloud2 pcl_msg;
144 
145  // Msg header
146  pcl_msg.header = std_msgs::Header();
147  pcl_msg.header.frame_id = "lidar";
148  // m_timestamp format: hhmmsszzz
149  time_t raw_time = ros::Time::now().toSec();
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 + // hh
156  (uint32_t)((m_timestamp / 100000) % 100) * 60 + // mm
157  (uint32_t)((m_timestamp / 1000) % 100); // ss
158  pcl_msg.header.stamp.nsec = (m_timestamp % 1000) * 1e6; // zzz
159 
160  pcl_msg.height = 1;
161  pcl_msg.width = size_pc;
162  pcl_msg.is_dense = true;
163 
164  // Total number of bytes per point
165  pcl_msg.point_step = sizeof(float) * 3 + sizeof(uint16_t) + sizeof(uint32_t); // x(4) + y(4) + z(4) + intensity(2) + rgb(4)
166  pcl_msg.row_step = pcl_msg.point_step * pcl_msg.width;
167  pcl_msg.data.resize(pcl_msg.row_step);
168 
169  // Modifier to describe what the fields are.
170  sensor_msgs::PointCloud2Modifier modifier(pcl_msg);
171  modifier.setPointCloud2Fields(5,
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);
177 
178  // Iterators for PointCloud msg
179  sensor_msgs::PointCloud2Iterator<float> iter_x(pcl_msg, pcl_msg.fields[0].name);
180  sensor_msgs::PointCloud2Iterator<float> iter_y(pcl_msg, pcl_msg.fields[1].name);
181  sensor_msgs::PointCloud2Iterator<float> iter_z(pcl_msg, pcl_msg.fields[2].name);
182  sensor_msgs::PointCloud2Iterator<uint16_t> iter_intensity(pcl_msg, pcl_msg.fields[3].name);
183  sensor_msgs::PointCloud2Iterator<uint32_t> iter_rgb(pcl_msg, pcl_msg.fields[4].name);
184 
185  for (int i = 0; i < size_pc; ++i)
186  {
187  *iter_y = -(float)data_received[5 * i + 1] / 1000.0;
188 
189  *iter_z = -(float)data_received[5 * i + 2] / 1000.0;
190 
191  *iter_x = (float)data_received[5 * i + 3] / 1000.0;
192 
193  *iter_intensity = (uint16_t)data_received[5 * i + 4];
194 
195  *iter_rgb = (uint32_t)data_received[5 * i + 5];
196 
197  ++iter_y;
198  ++iter_z;
199  ++iter_x;
200  ++iter_intensity;
201  ++iter_rgb;
202  }
203 
204  publisher.publish(pcl_msg);
205 
206  free(m_pointcloud_data);
207  points_received = 0;
208  pointcloud_index = 1;
209  }
210  else if (size_read > 0 && m_is_reading_pointcloud) // Data
211  {
212  int32_t points = 0;
213  memcpy(&points, &buffer[0], 4);
214  memcpy(&m_pointcloud_data[pointcloud_index], &buffer[4], (sizeof(int32_t) * (points * 5)));
215 
216  pointcloud_index += (points * 5);
217 
218  points_received += points;
219 
220  // check if under size
221  //if (points_received >= m_pointcloud_size)
222  // m_is_reading_pointcloud = false;
223  }
224  // size_read == -1 --> timeout
225  }
226 
227  publisher.shutdown();
228  ROS_INFO("Exiting lidar streaming thread");
229  free(buffer);
230  free(m_pointcloud_data);
231 
232  shutdown(m_socket_descriptor, SHUT_RDWR);
233  close(m_socket_descriptor);
234 
235  pthread_exit(0);
236 }
237 
238 namespace l3cam_ros
239 {
240  class LidarStream : public SensorStream
241  {
242  public:
243  explicit LidarStream() : SensorStream()
244  {
245  declareServiceServers("lidar");
246  }
247 
249 
250  private:
252  {
253  g_listening = false;
254  }
255 
256  }; // class LidarStream
257 
258 } // namespace l3cam_ros
259 
260 int main(int argc, char **argv)
261 {
262  ros::init(argc, argv, "lidar_stream");
263 
265 
266  // Check if service is available
267  ros::Duration timeout_duration(node->timeout_secs_);
268  if (!node->client_get_sensors_.waitForExistence(timeout_duration))
269  {
270  ROS_ERROR_STREAM(node->getNamespace() << " error: " << getErrorDescription(L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR) << ". Waited " << timeout_duration << " seconds");
272  }
273 
274  int error = L3CAM_OK;
275  bool sensor_is_available = false;
276  // Shutdown if sensor is not available or if error returned
277  if (node->client_get_sensors_.call(node->srv_get_sensors_))
278  {
279  error = node->srv_get_sensors_.response.error;
280 
281  if (!error)
282  {
283  for (int i = 0; i < node->srv_get_sensors_.response.num_sensors; ++i)
284  {
285  if (node->srv_get_sensors_.response.sensors[i].sensor_type == sensor_lidar && node->srv_get_sensors_.response.sensors[i].sensor_available)
286  {
287  sensor_is_available = true;
288  }
289  }
290  }
291  else
292  {
293  ROS_ERROR_STREAM(node->getNamespace() << " error " << error << " while checking sensor availability in " << __func__ << ": " << getErrorDescription(error));
294  return error;
295  }
296  }
297  else
298  {
299  ROS_ERROR_STREAM(node->getNamespace() << " error: Failed to call service get_sensors_available");
301  }
302 
303  if (sensor_is_available)
304  {
305  ROS_INFO("LiDAR available for streaming");
306  }
307  else
308  {
309  return 0;
310  }
311 
312  node->publisher_ = node->advertise<sensor_msgs::PointCloud2>("/PC2_lidar", 10);
313  std::thread thread(PointCloudThread, node->publisher_);
314  thread.detach();
315 
316  node->spin();
317 
318  node->publisher_.shutdown();
319  g_listening = false;
320  usleep(2000000);
321 
322  ros::shutdown();
323  return 0;
324 }
l3cam_ros::SensorStream
Definition: sensor_stream.hpp:38
point_cloud2_iterator.h
L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
#define L3CAM_ROS_SERVICE_AVAILABILITY_TIMEOUT_ERROR
Definition: l3cam_ros_errors.hpp:31
ros::Publisher
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
TimeBase< Time, Duration >::toSec
double toSec() const
ros::shutdown
ROSCPP_DECL void shutdown()
L3CAM_ROS_FAILED_TO_CALL_SERVICE
#define L3CAM_ROS_FAILED_TO_CALL_SERVICE
Definition: l3cam_ros_errors.hpp:29
l3cam_ros::LidarStream::stopListening
void stopListening()
Definition: lidar_stream.cpp:251
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
sensor_msgs::PointCloud2Modifier::setPointCloud2Fields
void setPointCloud2Fields(int n_fields,...)
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
g_listening
bool g_listening
Definition: lidar_stream.cpp:52
l3cam_ros::LidarStream
Definition: lidar_stream.cpp:240
shutdown
ROSCONSOLE_DECL void shutdown()
sensor_msgs::PointCloud2Iterator
ros::Publisher::shutdown
void shutdown()
PointCloudThread
void PointCloudThread(ros::Publisher publisher)
Definition: lidar_stream.cpp:54
l3cam_ros::SensorStream::declareServiceServers
void declareServiceServers(const std::string &sensor)
Definition: sensor_stream.cpp:51
l3cam_ros::LidarStream::LidarStream
LidarStream()
Definition: lidar_stream.cpp:243
ROS_WARN
#define ROS_WARN(...)
l3cam_ros::LidarStream::publisher_
ros::Publisher publisher_
Definition: lidar_stream.cpp:248
sensor_stream.hpp
getErrorDescription
static std::string getErrorDescription(int error_code)
Definition: l3cam_ros_utils.hpp:85
sensor_msgs::PointCloud2Modifier
main
int main(int argc, char **argv)
Definition: lidar_stream.cpp:260
node
l3cam_ros::L3Cam * node
Definition: l3cam_ros_node.cpp:41
ros::NodeHandle::getNamespace
const std::string & getNamespace() const
ROS_INFO
#define ROS_INFO(...)
ros::NodeHandle::shutdown
void shutdown()
ros::Duration
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