SICKAG / sick_scan_xd

Based on the sick_scan drivers for ROS1, sick_scan_xd merges sick_scan, sick_scan2 and sick_scan_base repositories. The driver supports both Linux (native, ROS1, ROS2) and Windows (native and ROS2).
Apache License 2.0
99 stars 84 forks source link

Using the API to get realtime scans #187

Closed SuhaibAlHindi closed 1 year ago

SuhaibAlHindi commented 1 year ago

I'm using a MRS1104C SICK LiDAR and I have noticed that when I open the interface of the LiDAR, it has a realtime scanning of the device but when I run this code, I found that the scans are much slower, each full scan takes about 1 sec.

Second note: the launch file sick_mrs_1xxx.launch does not support my LiDAR.

### launch file:

`

`

### code: ` def pySickScanCartesianPointCloudMsgToXYZ(pointcloud_msg): num_fields = pointcloud_msg.fields.size msg_fields_buffer = pointcloud_msg.fields.buffer field_offset_x = -1 field_offset_y = -1 field_offset_z = -1 for n in range(num_fields): field_name = ctypesCharArrayToString(msg_fields_buffer[n].name) field_offset = msg_fields_buffer[n].offset if field_name == "x": field_offset_x = msg_fields_buffer[n].offset elif field_name == "y": field_offset_y = msg_fields_buffer[n].offset elif field_name == "z": field_offset_z = msg_fields_buffer[n].offset cloud_data_buffer_len = (pointcloud_msg.row_step pointcloud_msg.height) # length of polar cloud data in byte assert(pointcloud_msg.data.size == cloud_data_buffer_len and field_offset_x >= 0 and field_offset_y >= 0 and field_offset_z >= 0) cloud_data_buffer = bytearray(cloud_data_buffer_len) for n in range(cloud_data_buffer_len): cloud_data_buffer[n] = pointcloud_msg.data.buffer[n] points_x = np.zeros(pointcloud_msg.width pointcloud_msg.height, dtype = np.float32) points_y = np.zeros(pointcloud_msg.width pointcloud_msg.height, dtype = np.float32) points_z = np.zeros(pointcloud_msg.width pointcloud_msg.height, dtype = np.float32) point_idx = 0 for row_idx in range(pointcloud_msg.height): for col_idx in range(pointcloud_msg.width): pointcloud_offset = row_idx pointcloud_msg.row_step + col_idx pointcloud_msg.point_step points_x[point_idx] = np.frombuffer(cloud_data_buffer, dtype = np.float32, count = 1, offset = pointcloud_offset + field_offset_x)[0] points_y[point_idx] = np.frombuffer(cloud_data_buffer, dtype = np.float32, count = 1, offset = pointcloud_offset + field_offset_y)[0] points_z[point_idx] = np.frombuffer(cloud_data_buffer, dtype = np.float32, count = 1, offset = pointcloud_offset + field_offset_z)[0] point_idx = point_idx + 1 return points_x, points_y, points_z

def pySickScanCartesianPointCloudMsgCallback(api_handle, pointcloud_msg): pointcloud_msg = pointcloud_msg.contents # dereference msg pointer (pointcloud_msg = pointcloud_msg[0]) plot_points_x, plot_points_y,plot_points_z = pySickScanCartesianPointCloudMsgToXYZ(pointcloud_msg) global x_points,y_points,z_points x_points = plot_points_x y_points = plot_points_y z_points = plot_points_z print(f"{plot_points_x},{np.max(plot_points_y):.2f}, and {np.max(plot_points_z):.2f}")

def pySickScanPolarPointCloudMsgCallback(api_handle, pointcloud_msg): global msg msg = pointcloud_msg pointcloud_msg = pointcloud_msg.contents # dereference msg pointer (pointcloud_msg = pointcloud_msg[0])

cartesian_pointcloud_callback = SickScanPointCloudMsgCallback(pySickScanCartesianPointCloudMsgCallback) SickScanApiRegisterCartesianPointCloudMsg(sick_scan_library, api_handle, cartesian_pointcloud_callback)`

rostest commented 1 year ago

Thank you for reporting this. Performance depends on the execution time of the callbacks. The Python function pySickScanCartesianPointCloudMsgToXYZ shows an example of how a point cloud message can be converted and visualized with matplotlib. For real-time processing, we recommend using C++ and/or ROS (ROS-1 or ROS-2 on Linux or Windows).

Please test the performance with a simple callback, that just prints a message:

# Simple callback for cartesian point cloud messages, just prints a message
def pySickScanCartesianPointCloudMsgCallback(api_handle, pointcloud_msg):
    pointcloud_msg = pointcloud_msg.contents # dereference msg pointer (pointcloud_msg = pointcloud_msg[0])
    print("pySickScanCartesianPointCloudMsgCallback: api_handle={}, {}x{} pointcloud".format(api_handle, pointcloud_msg.width, pointcloud_msg.height))

# Simple callback for polar point cloud messages, just prints a message
def pySickScanPolarPointCloudMsgCallback(api_handle, pointcloud_msg):
    pointcloud_msg = pointcloud_msg.contents # dereference msg pointer (pointcloud_msg = pointcloud_msg[0])
    print("pySickScanPolarPointCloudMsgCallback (ROS-{}): api_handle={}, {}x{} pointcloud".format(api_handle, pointcloud_msg.width, pointcloud_msg.height))

You should be receiving the pointcloud messages with the expected frequency. If this works as expected, you can process the data within the callback. We recommend to copy the scan data into a FIFO and to process the data in a separate thread to avoid bottlenecks due to blocking callbacks. For performance critical applications, we recommend to process the scan data using C++ and/or ROS.

The launch file sick_mrs_1xxx.launch should work, if you replace the default ip address of the lidar (i.e. "192.168.6.53" instead of "192.168.0.1"). Alternatively, you can overwrite parameter hostname by commandline. Did you get any error messages when using sick_mrs_1xxx.launch?

SuhaibAlHindi commented 1 year ago

Please test the performance with a simple callback, that just prints a message:


def pySickScanCartesianPointCloudMsgCallback(api_handle, pointcloud_msg):
pointcloud_msg = pointcloud_msg.contents # dereference msg pointer (pointcloud_msg = pointcloud_msg[0])
print("pySickScanCartesianPointCloudMsgCallback: api_handle={}, {}x{} pointcloud".format(api_handle, pointcloud_msg.width, pointcloud_msg.height))

Simple callback for polar point cloud messages, just prints a message

def pySickScanPolarPointCloudMsgCallback(api_handle, pointcloud_msg): pointcloud_msg = pointcloud_msg.contents # dereference msg pointer (pointcloud_msg = pointcloud_msg[0]) print("pySickScanPolarPointCloudMsgCallback (ROS-{}): api_handle={}, {}x{} pointcloud".format(api_handle, pointcloud_msg.width, pointcloud_msg.height))



I have tested it out, still not real time data.

> You should be receiving the pointcloud messages with the expected frequency. If this works as expected, you can process the data within the callback. We recommend to copy the scan data into a FIFO and to process the data in a separate thread to avoid bottlenecks due to blocking callbacks. For performance critical applications, we recommend to process the scan data using C++ and/or ROS.

Isn't there any solution with python?? 

> The launch file sick_mrs_1xxx.launch should work, if you replace the default ip address of the lidar (i.e. "192.168.6.53" instead of "192.168.0.1"). Alternatively, you can overwrite parameter `hostname` by commandline. Did you get any error messages when using sick_mrs_1xxx.launch?

It generates this error:

```ROS_DEBUG: Starting scan data ....

[Info]: Sending  : <STX><STX><STX><STX><Len=0029>sEN InertialMeasurementUnit 0x01 CRC:<0x35>
[Info]: Receiving: <STX>sEA InertialMeasurementUnit \x01<ETX>
ROS_INFO: SickScanServices: ros services initialized
ROS_INFO: Setup completed, sick_scan_xd is up and running.
ROS_INFO: Software PLL locking started, mapping ticks to system time.
[Info]: 1 / 6 packets dropped. Software PLL not yet locked.
pySickScanPolarPointCloudMsgCallback (ROS-0): api_handle=93978804841856, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): api_handle=93978804841856, 1101x4 pointcloud, 1 echo(s), segment 0
sick_scan_xd_api_test.py plotting pointcloud by matplotlib
Segmentation fault (core dumped)```

UPDATE01 : Found out that the error was caused by Matplotlib and the API test example.
rostest commented 1 year ago

Thanks for your feedback! We will analyze the python example in combination with the generic API and its performance with a MRS1104.

SuhaibAlHindi commented 1 year ago

Till you analyze the python example, How can I send direct telegram messages to the LiDAR in code?

rostest commented 1 year ago

You can send SOPAS telegrams to the lidar using the ROS service "ColaMsg", see https://github.com/SICKAG/sick_scan_xd/blob/master/USAGE.md#ros-services for details. ROS is required for this service. If this is an option, you can easily implement a python receiver for pointcloud messages, too. We recommend using ROS-1 or ROS-2.

rostest commented 1 year ago

I have tried out sick_scan_xd_api_test_minimal.py with the latest sick_scan_xd release on Linux in combination with a MRS1104 lidar. Unfortunately, I can not reproduce that error. Pointcloud messages were received in realtime with the expected frequency.

Please find attached sick_scan_xd_api_test_minimal.py and the logfile for details. sick_scan_xd_api_test_minimal.py is identical to sick_scan_xd_api_test.py, except for the visualization, which is disabled. The callbacks pySickScanCartesianPointCloudMsgCallback and pySickScanPolarPointCloudMsgCallback just print a short message incl. a timestamp (current time when pointcloud is received). You can see these timestamps in the logfile; the pointcloud messages are received with the scanner frequency.

Please build sick_scan_xd as described in https://github.com/SICKAG/sick_scan_xd/blob/master/INSTALL-GENERIC.md and https://github.com/SICKAG/sick_scan_xd/blob/master/doc/sick_scan_api/sick_scan_api.md. Run

pkill -f sick_scan_xd_api_test.py
pkill -f sick_scan_xd_api_test_minimal.py
python3 ./sick_scan_xd/test/python/sick_scan_xd_api/sick_scan_xd_api_test_minimal.py ./sick_scan_xd/launch/sick_mrs_1xxx.launch hostname:=192.168.6.53

We recommend ROS for processing pointclouds and lidar data. Alternatively, you might try the Numba jit-compiler for python, which can speed up python code by native compilation, especially for looping over big arrays. See https://numba.readthedocs.io/en/stable/ and https://numba.pydata.org/ for details. Using pointcloud libraries like PCL can also be an alternative, see https://pointclouds.org/ for details.

mrs1104_api_test.zip

SuhaibAlHindi commented 1 year ago

how can I make sure that the pointcloud messages are received with the chosen scanner frequency?

I ran the test provided and had the following log:

pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:29.376320, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:29.376421, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:30.175821, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:30.175937, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:30.976411, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:30.976555, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:31.774788, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:31.774922, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:32.573545, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:32.573666, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:33.373866, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:33.373983, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:34.172965, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:34.173085, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:34.972327, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:34.972434, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:35.771691, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:35.771799, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:36.570946, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:36.571066, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:37.371539, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:37.371684, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:38.170261, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:38.170393, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:38.969926, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:38.970073, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:39.770571, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:39.770722, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:40.568703, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:40.568851, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:41.367742, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:41.367873, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:42.167496, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:42.167612, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:42.967249, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:42.967365, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:43.766703, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:43.766827, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanPolarPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:44.566072, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
pySickScanCartesianPointCloudMsgCallback (ROS-0): timestamp=2023-07-16 11:01:44.566198, api_handle=94876907667824, 1101x4 pointcloud, 1 echo(s), segment 0
SuhaibAlHindi commented 1 year ago

The full log file: mrs1104.log

haven't tested out the Numba jit-compiler you mentioned yet.

SuhaibAlHindi commented 1 year ago

found out it was because of a mean filter that was defined in the SOPAS ET.

rostest commented 1 year ago

@SuhaibAlHindi Thanks for the explanation and for figuring out the problem!