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
95 stars 85 forks source link

Unable to successfully obtain point cloud data from window #243

Closed ghost closed 8 months ago

ghost commented 9 months ago

Hello, I am currently using sick multiscan136 lidar to obtain point cloud data under window. I have modified the corresponding hostname and udp_receiver_ip in the sick_multiscan.launch file, and used a timer to obtain real-time point cloud data from the minimum_sick_scan_api_client.cpp file. In the first few times, real-time point clouds can be obtained and saved, but during the running of the program, memory-related errors will be reported and cause the program to crash. Later, I have also modified the corresponding udp_receiver_ip and recompiled the program several times, but I was unable to obtain the point cloud data. The prompt message was:[Info]: SickScanServices: Request "sMN Run" successfully sent, received reply "sAN Run 1" [Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sMN Run", response: "sAN Run 1". Could you please tell me how to modify it to correctly obtain the point cloud data and solve the memory error? Thank you very much! ! !

231128090154 20231128090205

rostest commented 8 months ago

Thanks for your feedback. Note that minimum_sick_scan_api_client.cpp is a tiny API example. It just uses a sleep for some seconds as a placeholder for an application. Increase or replace this placeholder sleep, e.g. image

I can not reproduce any memory errors. Can you give some more information about your environment? Do you use Visual Studio 2019 for both sick_scan_xd library and minimum_sick_scan_api_client.exe? Did you build and run minimum_sick_scan_api_client.cpp as described in https://github.com/SICKAG/sick_scan_xd/blob/master/doc/sick_scan_api/sick_scan_api.md#minimalistic-usage-example-in-c-1, i.e. with just the print-statement in the callback?

ghost commented 8 months ago

Thank you very much for your reply. I am using window10 without ROS, and my compilation environment is Visual Studio Community 2019 Release -amd64. I followed the tutorial https://github.com/SICKAG/sick_scan_xd/blob/master/doc/sick_scan_api/sick_scan_api.md#minimalistic-usage-example-in-c-1 to compile the program using vs2019.When running in vs2019 or vscode , there will be problems such as being unable to obtain point clouds or reporting memory errors after obtaining point clouds. I used the pcl library to obtain real-time points and convert them into point clouds. I set a timer to save the point cloud files locally. Regarding the memory error, I originally thought that the code used to save the point cloud using pcl was wrong, but I commented out the relevant code,it still produces a memory error . Secondly, regarding placeholder sleep, I directly added a layer of looping outside. The main problem is that most of the time the point cloud cannot be obtained from the program. The following is the code after I changed minimum_sick_scan_api_client.cpp. Where might the problem lie? Thank you for your reply and help.

#include <chrono>
#include <iostream>
#include <thread>
// #ifndef PCL_NO_PRECOMPILE
#define PCL_NO_PRECOMPILE
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/io/pcd_io.h>
#include "sick_scan_xd_api/sick_scan_api.h"

#include <thread>
#include <mutex>

#include<time.h>
# define CATTIME 5000
int i=0;

pcl::PointCloud<pcl::PointXYZI>::Ptr mycloud (new pcl::PointCloud<pcl::PointXYZI>());
time_t begin,end;
std::mutex mylock;
// Implement a callback to process pointcloud messages
void customizedPointCloudMsgCb(SickScanApiHandle apiHandle, const SickScanPointCloudMsg* msg)
{
  // std::cout << "C++ PointCloudMsgCb: " << msg->width << " x " << msg->height << " pointcloud message received" << std::endl; // data processing to be done
  SickScanPointFieldMsg* msg_fields_buffer=(SickScanPointFieldMsg*)msg->fields.buffer;
  int offsetx=-1,offsety=-1,offsetz=-1,offseti=-1;
  for(int i=0;i<msg->fields.size;++i)
  {
      if(strcmp(msg_fields_buffer[i].name,"x")==0 && msg_fields_buffer[i].datatype==SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      {
        offsetx=msg_fields_buffer[i].offset;
      }
      if(strcmp(msg_fields_buffer[i].name,"y")==0 && msg_fields_buffer[i].datatype==SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      {
        offsety=msg_fields_buffer[i].offset;
      }
      if(strcmp(msg_fields_buffer[i].name,"z")==0 && msg_fields_buffer[i].datatype==SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      {
        offsetz=msg_fields_buffer[i].offset;
      }
      if(strcmp(msg_fields_buffer[i].name,"intensity")==0 && msg_fields_buffer[i].datatype==SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      {
        offseti=msg_fields_buffer[i].offset;
      }
      // if(x==0&&y==0&&z==0)
      // {
      //   continue;
      // }
      // pcl::PointXYZ point(x,y,z);
      // mycloud->push_back(point);
  }
  // std::cout<<"cloud size: "<<mycloud->size()<<std::endl;
  int img_width = 250 * 4, img_height = 250 * 4;
    uint8_t* img_pixel = (uint8_t*)calloc(3 * img_width * img_height, sizeof(uint8_t));
    for (int row_idx = 0; row_idx < (int)msg->height; row_idx++)
    {
        for (int col_idx = 0; col_idx < (int)msg->width; col_idx++)
        {
            // Get cartesian point coordinates
            int polar_point_offset = row_idx * msg->row_step + col_idx * msg->point_step;
            float point_x = *((float*)(msg->data.buffer + polar_point_offset + offsetx));
            float point_y = *((float*)(msg->data.buffer + polar_point_offset + offsety));
            float point_z = *((float*)(msg->data.buffer + polar_point_offset + offsetz));
            float point_intensity = 0;
            if (offseti >= 0)
                point_intensity = *((float*)(msg->data.buffer + polar_point_offset + offseti));
            if(point_x==0&&point_y==0&&point_z==0)
            {
              continue;
            }
            pcl::PointXYZI point(point_x, point_y, point_z,point_intensity);
            mylock.lock();
            //std::lock_guard<std::mutex> guard(mylock);
            mycloud->push_back(point);
            mylock.unlock();
            // Convert point coordinates in meter to image coordinates in pixel
            // int img_x = (int)(250.0f * (-point_y + 2.0f)); // img_x := -pointcloud.y
            // int img_y = (int)(250.0f * (-point_x + 2.0f)); // img_y := -pointcloud.x
            // if (img_x >= 0 && img_x < img_width && img_y >= 0 && img_y < img_height) // point within the image area
            // {
            //  img_pixel[3 * img_y * img_width + 3 * img_x + 0] = 255; // R
            //  img_pixel[3 * img_y * img_width + 3 * img_x + 1] = 255; // G
            //  img_pixel[3 * img_y * img_width + 3 * img_x + 2] = 255; // B
            // }
        }
    }
  end=clock();
  if(end-begin>=CATTIME)
  {
    ++i;
    begin=end;
    std::cout<< "receive "<<i<<" pointcloud"<<std::endl;
    // std::cout<<"cloud size: "<<mycloud->size()<<std::endl;
    pcl::io::savePCDFileBinary("E:/work/data/"+std::to_string(end)+".pcd",*mycloud);
    // pcl::io::savePCDFileASCII("E:/work/data/"+std::to_string(end)+".pcd",*mycloud);
    mycloud->clear();
  }

}

int main(int argc, char** argv)
{
  // Create a sick_scan instance and initialize lidar with commandline arguments
#ifdef _MSC_VER
    const char* sick_scan_api_lib = "sick_scan_xd_shared_lib.dll";
#else
    const char* sick_scan_api_lib = "libsick_scan_xd_shared_lib.so";
#endif
  SickScanApiLoadLibrary(sick_scan_api_lib);
  argc=4;
  argv[0]=".E:/work/code/sick_scan_ws/build/Release/minimum_sick_scan_api_client.exe";
  argv[1]="E:/work/code/sick_scan_ws/sick_scan_xd/launch/sick_multiscan.launch";
  argv[2]="hostname:=192.168.10.230";
  argv[3]="udp_receiver_ip:=192.168.10.99";
  SickScanApiHandle apiHandle = SickScanApiCreate(argc, argv);
  SickScanApiInitByCli(apiHandle, argc, argv);
  begin= clock();
  // Register for pointcloud messages
  SickScanApiRegisterCartesianPointCloudMsg(apiHandle, &customizedPointCloudMsgCb);

  // Run application or main loop
  // getchar();
  while (true)
  {
  std::this_thread::sleep_for(std::chrono::seconds(15));
  }

  // Close lidar and release sick_scan api
  SickScanApiDeregisterCartesianPointCloudMsg(apiHandle, &customizedPointCloudMsgCb);
  SickScanApiClose(apiHandle);
  SickScanApiRelease(apiHandle);
  SickScanApiUnloadLibrary();
}

image

rostest commented 8 months ago

Thanks for your reply. Without having tested your example, I would recommend a few modifications:

We recommend to copy the scan data to a threadsafe FIFO within the callback and to perform all data processing (like saving scans to disk) in a separate thread or the main loop. This way the callback will not be blocked during data processing.

If the last line printed on the console is sAN Run 1 (as it is on your screenshot), sick_scan_xd most likely does not receive any scan data from the lidar via UDP. Make sure that udp_receiver_ip is correct (i.e. the ip address of your PC running minimum_sick_scan_api_client.exe). Open //192.168.10.230 in a browser and use SOPAS Air to check the pointcloud and settings. Deactivating and activating UDP scan data can help. If the problem remains, restart both minimum_sick_scan_api_client.exe and the lidar.

ghost commented 8 months ago

Thank you very much for your careful and detailed reply! ! Sorry for the late reply as I have been busy recently. Regarding the variable img_pixel, I'm sorry to find that I forgot to comment it. The subsequent code correction also gave me a lot of inspiration. I have made the correction according to the method you said, and opened another thread to process the point cloud in the callback. Very few people read the code I wrote so carefully. Thank you again for your patience and help; Regarding the inability to obtain the point cloud data of the radar, I found that it may be because after pressing ctrl+c to interrupt the program, the subsequent release-related code was not executed, causing the port to be occupied the next time the program was executed, and the point cloud data could not be obtained by udp. I added code to capture keyboard signals to ensure subsequent release operations work properly. However, I found that after adding the relevant code, the point cloud was still unable to be obtained. Using the netstat -ano | findstr command in the cmd window, I found that ports 2111 and 2115 were not occupied, but the point cloud was still unable to be obtained.However, I can see the point cloud when I enter the corresponding IP address of the lidar in the browser. What may be the problem?

scanner_type                   string     sick_multiscan
hostname                       string     192.168.0.237
udp_receiver_ip                string     192.168.0.236
udp_sender                     string
udp_port                       int        2115
segment_count                  int        12
publish_frame_id               string     world
udp_input_fifolength           int        20
msgpack_output_fifolength      int        20
verbose_level                  int        1
measure_timing                 bool       True
export_csv                     bool       False
export_udp_msg                 bool       False
logfolder                      string
udp_timeout_ms                 int        60000
scandataformat                 int        2
range_min                      double     0.0
range_max                      double     100.0
range_filter_handling          int        0
add_transform_xyz_rpy          string     0,0,0,0,0,0
add_transform_check_dynamic_updates bool       false
sopas_tcp_port                 string     2111
start_sopas_service            bool       True
send_sopas_start_stop_cmd      bool       True
sopas_cola_binary              bool       False
sopas_timeout_ms               int        5000
client_authorization_pw        string     F4724744
host_read_filtersettings       bool       True
host_FREchoFilter              int        2
host_set_FREchoFilter          bool       True
host_LFPangleRangeFilter       string     0 -180.0 +179.0 -90.0 +90.0 1
host_set_LFPangleRangeFilter   bool       False
host_LFPlayerFilter            string     0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0
host_set_LFPlayerFilter        bool       False
msgpack_validator_enabled      bool       False
msgpack_validator_verbose      int        1
msgpack_validator_discard_msgpacks_out_of_bounds bool       True
msgpack_validator_check_missing_scandata_interval int        12
msgpack_validator_required_echos string     0
msgpack_validator_azimuth_start double     -180.0
msgpack_validator_azimuth_end  double     +180.0
msgpack_validator_elevation_start double     -90.0
msgpack_validator_elevation_end double     +90.0
msgpack_validator_valid_segments string     0 1 2 3 4 5 6 7 8 9 10 11
msgpack_validator_layer_filter string     0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0
ros_qos                        int        -1
laserscan_layer_filter         string     0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0
custom_pointclouds             string     cloud_unstructured_segments cloud_unstructured_fullframe cloud_polar_unstructured_segments cloud_polar_unstructured_fullframe cloud_all_fields_fullframe
cloud_unstructured_segments    string     coordinateNotation=0 updateMethod=1 echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_segments frameid=world publish=1
cloud_unstructured_fullframe   string     coordinateNotation=0 updateMethod=0 echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_fullframe frameid=world publish=1
cloud_polar_unstructured_segments string     coordinateNotation=1 updateMethod=1 echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_polar_unstructured_segments frameid=world publish=1
cloud_polar_unstructured_fullframe string     coordinateNotation=1 updateMethod=0 echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_polar_unstructured_fullframe frameid=world publish=1
cloud_unstructured_echo1       string     coordinateNotation=0 updateMethod=0 echos=0 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_echo1 frameid=world publish=1cloud_unstructured_echo1_segments string     coordinateNotation=0 updateMethod=1 echos=0 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_echo1_segments frameid=world publish=1
cloud_unstructured_echo2       string     coordinateNotation=0 updateMethod=0 echos=1 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_echo2 frameid=world publish=1cloud_unstructured_echo2_segments string     coordinateNotation=0 updateMethod=1 echos=1 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_echo2_segments frameid=world publish=1
cloud_unstructured_echo3       string     coordinateNotation=0 updateMethod=0 echos=2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_echo3 frameid=world publish=1cloud_unstructured_echo3_segments string     coordinateNotation=0 updateMethod=1 echos=2 layers=6,14 reflectors=1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_echo3_segments frameid=world publish=1
cloud_unstructured_reflector   string     coordinateNotation=0 updateMethod=0 echos=0,1,2 layers=6,14 reflectors=1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_reflector frameid=world publish=1
cloud_unstructured_reflector_segments string     coordinateNotation=0 updateMethod=1 echos=0,1,2 layers=6,14 reflectors=1 infringed=0,1 rangeFilter=0.05,999,1 topic=/cloud_unstructured_reflector_segments frameid=world publish=1
cloud_structured_hires0        string     coordinateNotation=3 updateMethod=0 fields=x,y,z,i,range,azimuth,elevation echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_structured_hires0 frameid=world publish=1
cloud_structured_hires0_segments string     coordinateNotation=3 updateMethod=1 fields=x,y,z,i,range,azimuth,elevation echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_structured_hires0_segments frameid=world publish=1
cloud_structured_hires1        string     coordinateNotation=3 updateMethod=0 fields=x,y,z,i,range,azimuth,elevation echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_structured_hires1 frameid=world publish=1
cloud_structured_hires1_segments string     coordinateNotation=3 updateMethod=1 fields=x,y,z,i,range,azimuth,elevation echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_structured_hires1_segments frameid=world publish=1
cloud_structured               string     coordinateNotation=3 updateMethod=0 fields=x,y,z,i,range,azimuth,elevation echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_structured frameid=world publish=1
cloud_structured_segments      string     coordinateNotation=3 updateMethod=1 fields=x,y,z,i,range,azimuth,elevation echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_structured_segments frameid=world publish=1
cloud_all_fields_segments      string     coordinateNotation=3 updateMethod=1 fields=x,y,z,i,range,azimuth,elevation,layer,echo,reflector echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_all_fields_segments frameid=world publish=1
cloud_all_fields_fullframe     string     coordinateNotation=3 updateMethod=0 fields=x,y,z,i,range,azimuth,elevation,layer,echo,reflector echos=0,1,2 layers=6,14 reflectors=0,1 infringed=0,1 rangeFilter=0,999,0 topic=/cloud_all_fields_fullframe frameid=world publish=1
[Info]: SickCloudTransform: add_transform_xyz_rpy = (0,0,0,0,0,0)
[Info]: SickCloudTransform: azimuth_offset = 0 [deg]
[Info]: SickCloudTransform: additional 3x3 rotation matrix = { (1,0,0), (0,1,0), (0,0,1) }
[Info]: SickCloudTransform: apply 3x3 rotation = false
[Info]: SickCloudTransform: additional translation = (0,0,0)
[Info]: SickCloudTransform: check_dynamic_updates = false
[Info]: Range filter configuration for sick_scansegment_xd: range_min=0, range_max=100, range_filter_handling=0
[Info]: sick_scansegment_xd configuration:
[Info]: scanner_type:                     sick_multiscan
[Info]: udp_sender:
[Info]: udp_port:                         2115
[Info]: all_segments_min_deg:             -180
[Info]: all_segments_max_deg:             180
[Info]: publish_frame_id:                 world
[Info]: udp_input_fifolength:             20
[Info]: msgpack_output_fifolength:        20
[Info]: verbose_level:                    1
[Info]: measure_timing:                   1
[Info]: export_csv:                       0
[Info]: export_udp_msg:                   0
[Info]: logfolder:
[Info]: hostname:                         192.168.0.237
[Info]: udp_receiver_ip:                  192.168.0.236
[Info]: udp_timeout_ms:                   60000
[Info]: scandataformat:                   2
[Info]: sopas_tcp_port:                   2111
[Info]: start_sopas_service:              1
[Info]: send_sopas_start_stop_cmd:        1
[Info]: sopas_cola_binary:                0
[Info]: sopas_timeout_ms:                 5000
[Info]: host_read_filtersettings:         1
[Info]: host_FREchoFilter:                2
[Info]: host_set_FREchoFilter:            1
[Info]: host_LFPangleRangeFilter:         0 -180.0 +179.0 -90.0 +90.0 1
[Info]: host_set_LFPangleRangeFilter:     0
[Info]: host_LFPlayerFilter:              0 0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0
[Info]: host_set_LFPlayerFilter:          0
[Info]: laserscan_layer_filter:           0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0
[Info]: msgpack_validator_enabled:                         0
[Info]: msgpack_validator_verbose:                         1
[Info]: msgpack_validator_discard_msgpacks_out_of_bounds:  1
[Info]: msgpack_validator_check_missing_scandata_interval: 12
[Info]: msgpack_validator_required_echos:                  0
[Info]: msgpack_validator_azimuth_start:                   -3.14159 [rad]
[Info]: msgpack_validator_azimuth_end:                     3.14159 [rad]
[Info]: msgpack_validator_elevation_start:                 -1.5708 [rad]
[Info]: msgpack_validator_elevation_end:                   1.5708 [rad]
[Info]: msgpack_validator_valid_segments:                  0 1 2 3 4 5 6 7 8 9 10 11
[Info]: msgpack_validator_layer_filter:                    0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0
[Info]: sick_scansegment_xd (sick_multiscan) started.
[Info]: sick_scansegment_xd initializing...
[Info]: UdpReceiverSocketImpl: udp socket created, binding to port 2115 ...
[Info]: sick_scansegment_xd: udp socket to :2115 initialized
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): publish = 1
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): topic = /cloud_unstructured_segments
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): frameid = world
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): coordinate_notation = 0
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): update_method = 1
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): fields_enabled = i,x,y,z
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): echos_enabled = 0,1,2
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): layers_enabled = 5,13
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): reflector_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): infringed_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_unstructured_segments): range_filter = (0.050,999.000,1)
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): publish = 1
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): topic = /cloud_unstructured_fullframe
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): frameid = world
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): coordinate_notation = 0
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): update_method = 0
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): fields_enabled = i,x,y,z
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): echos_enabled = 0,1,2
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): layers_enabled = 5,13
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): reflector_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): infringed_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_unstructured_fullframe): range_filter = (0.050,999.000,1)
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): publish = 1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): topic = /cloud_polar_unstructured_segments
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): frameid = world
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): coordinate_notation = 1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): update_method = 1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): fields_enabled = azimuth,elevation,i,range
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): echos_enabled = 0,1,2
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): layers_enabled = 5,13
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): reflector_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): infringed_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_segments): range_filter = (0.050,999.000,1)
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): publish = 1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): topic = /cloud_polar_unstructured_fullframe
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): frameid = world
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): coordinate_notation = 1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): update_method = 0
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): fields_enabled = azimuth,elevation,i,range
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): echos_enabled = 0,1,2
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): layers_enabled = 5,13
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): reflector_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): infringed_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_polar_unstructured_fullframe): range_filter = (0.050,999.000,1)
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): publish = 1
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): topic = /cloud_all_fields_fullframe
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): frameid = world
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): coordinate_notation = 3
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): update_method = 0
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): fields_enabled = azimuth,echo,elevation,i,layer,range,reflector,x,y,z
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): echos_enabled = 0,1,2
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): layers_enabled = 5,13
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): reflector_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): infringed_enabled = 0,1
[Info]: CustomPointCloudConfiguration(cloud_all_fields_fullframe): range_filter = (0.000,999.000,0)
[Info]: MsgPackThreads: Start msgpack converter, udp receiver and msgpack exporter, receiving from :2115
[Info]: MsgPackThreads: initializing sopas tcp (192.168.0.237:2111, timeout:5, binary:0)
[Info]: Publishing lidar pointcloud2 to
[Info]: Publishing on topic "/", qos=10
[Info]: Publishing on topic "/imu", qos=10
[Info]: Publishing on topic "/encoder", qos=10
[Info]: Publishing on topic "/scan", qos=10
[Info]: SickCloudTransform: add_transform_xyz_rpy = (0,0,0,0,0,0)
[Info]: SickCloudTransform: azimuth_offset = 0 [deg]
[Info]: SickCloudTransform: additional 3x3 rotation matrix = { (1,0,0), (0,1,0), (0,0,1) }
[Info]: SickCloudTransform: apply 3x3 rotation = false
[Info]: SickCloudTransform: additional translation = (0,0,0)
[Info]: SickCloudTransform: check_dynamic_updates = false
[Info]: MsgPackThreads: initializing device
[Info]: sick_scan_xd: Tcp::open: connecting to 192.168.0.237:2111 ...
[Info]: sick_scan_xd Tcp::open: connected to 192.168.0.237:2111[Info]: SickThread TcpRecvThread started.

[Info]: MsgPackThreads: initializing services
[Info]: MsgPackThreads: ros services initialized
[Info]: SickScanServices: Sending request "sMN SetAccessMode 3 F4724744"
[Info]: Sending  : <STX>sMN SetAccessMode 3 F4724744<ETX>
[Info]: Receiving: <STX>sAN SetAccessMode 1<ETX>
[Info]: SickScanServices: Request "sMN SetAccessMode 3 F4724744" successfully sent, received reply "sAN SetAccessMode 1"
[Info]: SickScanServices: request: "sMN SetAccessMode 3 F4724744"
[Info]: SickScanServices: response: "sAN SetAccessMode 1"
[Info]: SickScanServices: Sending request "sWN FREchoFilter 2"
[Info]: Sending  : <STX>sWN FREchoFilter 2<ETX>
[Info]: Receiving: <STX>sWA FREchoFilter<ETX>
[Info]: SickScanServices: Request "sWN FREchoFilter 2" successfully sent, received reply "sWA FREchoFilter"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sWN FREchoFilter 2", response: "sWA FREchoFilter"
[Info]: SickScanServices: Sending request "sMN Run"
[Info]: Sending  : <STX>sMN Run<ETX>
[Info]: Receiving: <STX>sAN Run 1<ETX>
[Info]: SickScanServices: Request "sMN Run" successfully sent, received reply "sAN Run 1"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sMN Run", response: "sAN Run 1"
[Info]: SickScanServices: Sending request "sMN SetAccessMode 3 F4724744"
[Info]: Sending  : <STX>sMN SetAccessMode 3 F4724744<ETX>
[Info]: Receiving: <STX>sAN SetAccessMode 1<ETX>
[Info]: SickScanServices: Request "sMN SetAccessMode 3 F4724744" successfully sent, received reply "sAN SetAccessMode 1"
[Info]: SickScanServices: request: "sMN SetAccessMode 3 F4724744"
[Info]: SickScanServices: response: "sAN SetAccessMode 1"
[Info]: SickScanServices: Sending request "sRN FREchoFilter"
[Info]: Sending  : <STX>sRN FREchoFilter<ETX>
[Info]: Receiving: <STX>sRA FREchoFilter 2<ETX>
[Info]: SickScanServices: Request "sRN FREchoFilter" successfully sent, received reply "sRA FREchoFilter 2"
[Info]: SickScanServices: Sending request "sRN LFPangleRangeFilter"
[Info]: Sending  : <STX>sRN LFPangleRangeFilter<ETX>
[Info]: Receiving: <STX>sRA LFPangleRangeFilter 0 BFC90FDB 3FC90FDB BFC90FF9 3FC90FF9 1<ETX>
[Info]: SickScanServices: Request "sRN LFPangleRangeFilter" successfully sent, received reply "sRA LFPangleRangeFilter 0 BFC90FDB 3FC90FDB BFC90FF9 3FC90FF9 1"
[Info]: SickScanServices: Sending request "sRN LFPlayerFilter"
[Info]: Sending  : <STX>sRN LFPlayerFilter<ETX>
[Info]: Receiving: <STX>sRA LFPlayerFilter 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1<ETX>
[Info]: SickScanServices: Request "sRN LFPlayerFilter" successfully sent, received reply "sRA LFPlayerFilter 0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1"
[Info]: SickScanServices::queryMultiScanFiltersettings(): FREchoFilter: "2" = {2}
[Info]: SickScanServices::queryMultiScanFiltersettings(): LFPangleRangeFilter: "0 BFC90FDB 3FC90FDB BFC90FF9 3FC90FF9 1" = {0,BFC90FDB,3FC90FDB,BFC90FF9,3FC90FF9,1}
[Info]: SickScanServices::queryMultiScanFiltersettings(): LFPlayerFilter: "0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1" = {0,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1}
[Info]: SickScanServices::queryMultiScanFiltersettings(): sopas.FREchoFilter = "2", sopas.LFPangleRangeFilter = "0 -107734 107014 -107734 107014 1", sopas.LFPlayerFilter = "0 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 
1"
[Info]: SickScanServices::queryMultiScanFiltersettings(): msgpack_validator_required_echos = { 0 }, msgpack_validator_angles = { -3.14159 3.14159 -1.5708 1.5708 } [rad], msgpack_validator_layer_filter = { 
0 0 0 0 0 1 0 0 0 0 0 0 0 1 0 0 }
[Info]: SickScanServices: Sending request "sMN SetAccessMode 3 F4724744"
[Info]: Sending  : <STX>sMN SetAccessMode 3 F4724744<ETX>
[Info]: Receiving: <STX>sAN SetAccessMode 1<ETX>
[Info]: SickScanServices: Request "sMN SetAccessMode 3 F4724744" successfully sent, received reply "sAN SetAccessMode 1"
[Info]: SickScanServices: request: "sMN SetAccessMode 3 F4724744"
[Info]: SickScanServices: response: "sAN SetAccessMode 1"
[Info]: SickScanServices: Sending request "sWN ScanDataEthSettings 1 +192 +168 +0 +236 +2115"
[Info]: Sending  : <STX>sWN ScanDataEthSettings 1 +192 +168 +0 +236 +2115<ETX>
[Info]: Receiving: <STX>sWA ScanDataEthSettings<ETX>
[Info]: SickScanServices: Request "sWN ScanDataEthSettings 1 +192 +168 +0 +236 +2115" successfully sent, received reply "sWA ScanDataEthSettings"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sWN ScanDataEthSettings 1 +192 +168 +0 +236 +2115", response: "sWA ScanDataEthSettings"
[Info]: SickScanServices: Sending request "sWN ScanDataFormat 2"
[Info]: Sending  : <STX>sWN ScanDataFormat 2<ETX>
[Info]: Receiving: <STX>sWA ScanDataFormat<ETX>
[Info]: SickScanServices: Request "sWN ScanDataFormat 2" successfully sent, received reply "sWA ScanDataFormat"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sWN ScanDataFormat 2", response: "sWA ScanDataFormat"
[Info]: SickScanServices: Sending request "sWN ScanDataPreformatting 1"
[Info]: Sending  : <STX>sWN ScanDataPreformatting 1<ETX>
[Info]: Receiving: <STX>sWA ScanDataPreformatting<ETX>
[Info]: SickScanServices: Request "sWN ScanDataPreformatting 1" successfully sent, received reply "sWA ScanDataPreformatting"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sWN ScanDataPreformatting 1", response: "sWA ScanDataPreformatting"
[Info]: SickScanServices: Sending request "sWN ScanDataEnable 1"
[Info]: Sending  : <STX>sWN ScanDataEnable 1<ETX>
[Info]: Receiving: <STX>sWA ScanDataEnable<ETX>
[Info]: SickScanServices: Request "sWN ScanDataEnable 1" successfully sent, received reply "sWA ScanDataEnable"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sWN ScanDataEnable 1", response: "sWA ScanDataEnable"
[Info]: SickScanServices: Sending request "sMN LMCstartmeas"
[Info]: Sending  : <STX>sMN LMCstartmeas<ETX>
[Info]: Receiving: <STX>sAN LMCstartmeas 0<ETX>
[Info]: SickScanServices: Request "sMN LMCstartmeas" successfully sent, received reply "sAN LMCstartmeas 0"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sMN LMCstartmeas", response: "sAN LMCstartmeas 0"
[Info]: SickScanServices: Sending request "sMN Run"
[Info]: Sending  : <STX>sMN Run<ETX>
[Info]: Receiving: <STX>sAN Run 1<ETX>
[Info]: SickScanServices: Request "sMN Run" successfully sent, received reply "sAN Run 1"
[Info]: SickScanServices::sendSopasCmdCheckResponse(): request: "sMN Run", response: "sAN Run 1"
rostest commented 8 months ago

Thanks for following up. Since the last line printed is sAN Run 1, sick_scan_xd most likely does not receive any scan data from the lidar via UDP. Please open //192.168.0.237 (i.e. the ip address of your multiScan lidar) in a browser and use SOPAS Air to check the pointcloud and settings. If you can view the pointcloud in SOPAS Air, please check that the configuration of parameter udp_receiver_ip:=192.168.0.236 (i.e. the ip address of your PC) is correct and identical to the receiver ip address displayed in SOPAS Air. If SOPAS Air does not display the expected pointcloud, check the UDP network settings in SOPAS Air.

After SOPAS Air displays the expected pointcloud, make sure that parameter udp_receiver_ip (i.e. 192.168.0.236 in your logfile) is identical to the configuration in SOPAS Air and retry.

If you still do not receive any pointcloud messages, but you can see the pointcloud in SOPAS Air, please send screenshots from the SOPAS Air settings, such that we can help with the configuration.

ghost commented 8 months ago

Thank you very much for your reply. Every time i open the browser using IP, i can see some cloud data on the browser.When using the program minimum_sick_scan_api_client.cpp, the point cloud data can be obtained in a few cases. If the program ends normally, the point cloud data can also be obtained. However, after exiting the program using ctrl+c, when I re-execute the program again,the point cloud data cannot be obtained in most cases. I tried to use signal(SIGINT, sigint_handler); to capture the ctrl+c signal and perform the release operation in the corresponding sigint_handler function, but I still cannot obtain the point cloud. No port occupation was found using netstat -ano | findstr. image image image image

rostest commented 8 months ago

Thanks for following up. Just to make sure we have the same understanding of the problem: If you start minimum_sick_scan_api_client.cpp for the very first time, you obtain the pointcloud data via the sick_scan_xd API as expected. After Ctrl-C, program exit and restart, you sometimes get a pointcloud, but mostly you do not. Is this correct?

In this case it looks like the multiScan might not reopen/reset the UDP socket after the TCP connection is lost (i.e. after program exit). Please try the following:

  1. Restart the lidar (power down and up) and wait until multiScan is ready.
  2. Start minimum_sick_scan_api_client and make sure the callback (i.e. function customizedPointCloudMsgCb) is getting called.
  3. Stop minimum_sick_scan_api_client (Ctrl-C) and wait until it has exited.
  4. Restart the lidar (power down and up) and wait until multiScan is ready.
  5. Restart minimum_sick_scan_api_client. Does minimum_sick_scan_api_client receive a pointcloud now, i.e. does it work if both multiScan and minimum_sick_scan_api_client are restarted? If so, please retry a few times to make sure the behaviour is reproducable.

If this is the case, please run these steps again, but instead of restarting the multiScan lidar, just Disable and Enable the "Measurement Data Output" in SOPAS Air. Is the minimum_sick_scan_api_client working reproducable after restart, if "Measurement Data Output" has been disabled and enabled before? If so, an additional IP reset might be required between two restarts.

Btw: The implementation in function customizedPointCloudMsgCb appends a shallow copy of the received message in dataQueue. This is unsafe, because allocated message memory is released by sick_scan_xd after executing the callback. This might cause dangling pointer somewhere else in the application. Please make and push a deep copy of the message, e.g.:

class PointXYZI
{
public:
  float x;
  float y;
  float z;
  float i;
};
// Get offsets for x, y, z, intensity values
SickScanPointFieldMsg* msg_fields_buffer = msg->fields.buffer;
int field_offset_x = -1, field_offset_y = -1, field_offset_z = -1, field_offset_intensity = -1;
for (int n = 0; n < msg->fields.size; n++)
{
  if (strcmp(msg_fields_buffer[n].name, "x") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
    field_offset_x = msg_fields_buffer[n].offset;
  else if (strcmp(msg_fields_buffer[n].name, "y") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
    field_offset_y = msg_fields_buffer[n].offset;
  else if (strcmp(msg_fields_buffer[n].name, "z") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
    field_offset_z = msg_fields_buffer[n].offset;
  else if (strcmp(msg_fields_buffer[n].name, "intensity") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
    field_offset_intensity = msg_fields_buffer[n].offset;
}
assert(field_offset_x >= 0 && field_offset_y >= 0 && field_offset_z >= 0);
// Concatenate all points to a vector
std::vector<PointXYZI> point_field;
point_field.reserve(msg->width* msg->height);
for (int row_idx = 0; row_idx < (int)msg->height; row_idx++)
{
  for (int col_idx = 0; col_idx < (int)msg->width; col_idx++)
  {
    // Get cartesian point coordinates
    PointXYZI point_xyzi;
    int point_offset = row_idx * msg->row_step + col_idx * msg->point_step;
    point_xyzi.x = *((float*)(msg->data.buffer + point_offset + field_offset_x));
    point_xyzi.y = *((float*)(msg->data.buffer + point_offset + field_offset_y));
    point_xyzi.z = *((float*)(msg->data.buffer + point_offset + field_offset_z));
    point_xyzi.i = 0;
    if (field_offset_intensity >= 0)
      point_xyzi.i = *((float*)(msg->data.buffer + point_offset + field_offset_intensity));
    point_field.push_back(point_xyzi);
  }
}
dataQueue.push(point_field);
ghost commented 8 months ago

Thank you very much for your patient reply. According to what you said, I changed the copy method of the dataQueue in the callback and performed subsequent processing on it in another thread. Secondly, as you said, when the sAN Run 1 prompt appears and the data cannot be obtained, close and reopen the radar or Disable and Enable the "Measurement Data Output" in SOPAS Air, and then open the program again ,it can obtain the point cloud normally. When I think about how to write the program so that I don't have to manually close and reopen the radar or Disable and Enable the "Measurement Data Output" in SOPAS Air after each ctrl+c interrupt. I found that after modifying the code as follows, even after ctrl+c interrupts the program, the point cloud data can be obtained normally during the next execution. Thank you again, you really helped me a lot. You are such a kind and patient person, I wish you happy every day :D

#include <chrono>
#include <iostream>
#include <thread>
#include <signal.h>
#include <mutex>
#include <time.h>
#include <queue>
#ifndef PCL_NO_PRECOMPILE
#define PCL_NO_PRECOMPILE
#endif
#include <pcl/point_types.h>
#include <pcl/point_cloud.h>
#include <pcl/io/pcd_io.h>
#include "sick_scan_xd_api/sick_scan_api.h"
#include <iomanip>

bool app_stopped = false;
SickScanApiHandle apiHandle1;
pcl::PointCloud<pcl::PointXYZI>::Ptr mycloud (new pcl::PointCloud<pcl::PointXYZI>());
time_t begin,end;
std::mutex mylock;
std::condition_variable mycond;
std::queue<pcl::PointCloud<pcl::PointXYZI>> dataQueue;

std::string getCurrentTime()
{
  auto now = std::chrono::system_clock::now();
  std::time_t now_c = std::chrono::system_clock::to_time_t(now);
  std::tm timeInfo = *std::localtime(&now_c);
  std::stringstream ss;
  ss << std::put_time(&timeInfo, "%Y%m%d%H%M%S");
  return ss.str();
}

// Implement a callback to process pointcloud messages
void customizedPointCloudMsgCb(SickScanApiHandle apiHandle, const SickScanPointCloudMsg* msg)
{
  if (app_stopped)
  {
      return ;
  } 
  std::cout<<"++++++++++++++++++++++++++++++++++++++++++++++++"<<std::endl;
  SickScanPointFieldMsg* msg_fields_buffer = msg->fields.buffer;
  int field_offset_x = -1, field_offset_y = -1, field_offset_z = -1, field_offset_intensity = -1;
  for (int n = 0; n < msg->fields.size; n++)
  {
    if (strcmp(msg_fields_buffer[n].name, "x") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      field_offset_x = msg_fields_buffer[n].offset;
    else if (strcmp(msg_fields_buffer[n].name, "y") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      field_offset_y = msg_fields_buffer[n].offset;
    else if (strcmp(msg_fields_buffer[n].name, "z") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      field_offset_z = msg_fields_buffer[n].offset;
    else if (strcmp(msg_fields_buffer[n].name, "intensity") == 0 && msg_fields_buffer[n].datatype == SICK_SCAN_POINTFIELD_DATATYPE_FLOAT32)
      field_offset_intensity = msg_fields_buffer[n].offset;
  }
  assert(field_offset_x >= 0 && field_offset_y >= 0 && field_offset_z >= 0);
  std::unique_lock<std::mutex> lockGuard(mylock);
  pcl::PointCloud<pcl::PointXYZI> point_field;
  point_field.reserve(msg->width* msg->height);
  for (int row_idx = 0; row_idx < (int)msg->height; row_idx++)
  {
    for (int col_idx = 0; col_idx < (int)msg->width; col_idx++)
    {
      pcl::PointXYZI point_xyzi;
      int point_offset = row_idx * msg->row_step + col_idx * msg->point_step;
      point_xyzi.x = *((float*)(msg->data.buffer + point_offset + field_offset_x));
      point_xyzi.y = *((float*)(msg->data.buffer + point_offset + field_offset_y));
      point_xyzi.z = *((float*)(msg->data.buffer + point_offset + field_offset_z));
      point_xyzi.intensity = 0;
      if (field_offset_intensity >= 0)
        point_xyzi.intensity = *((float*)(msg->data.buffer + point_offset + field_offset_intensity));
      point_field.push_back(point_xyzi);
    }
  }
  dataQueue.push(point_field);
  lockGuard.unlock();
  mycond.notify_all();
}

void sigint_handler(int sig){
    if(sig == SIGINT){
    std::cout << "ctrl+c pressed!" << std::endl;
    // app_stopped = true;
  SickScanApiDeregisterCartesianPointCloudMsg(apiHandle1, &customizedPointCloudMsgCb);
  SickScanApiClose(apiHandle1);
  SickScanApiRelease(apiHandle1);
  SickScanApiUnloadLibrary();
    }
}

void fun()
{
  while(true)
  {
    if (app_stopped)
    {
        break;
    } 
    // why data does not go into this thread
    std::unique_lock<std::mutex> lock(mylock);
    mycond.wait(lock,[]{return !dataQueue.empty();});
    pcl::PointCloud<pcl::PointXYZI> msg = dataQueue.front(); 
    dataQueue.pop();
    std::string currentTime=getCurrentTime();
    std::cout<<"-------------------------------------------- "<<currentTime<<std::endl;
    // how long to take and clean a cloud 
    // why saving point cloud will make the progress break 
    // pcl::io::savePCDFileBinary("E:/desktop/231219/"+currentTime+".pcd",msg);
    msg.clear();
  }
}

int main(int argc, char** argv)
{
try{
  // Create a sick_scan instance and initialize lidar with commandline arguments
#ifdef _MSC_VER
    const char* sick_scan_api_lib = "sick_scan_xd_shared_lib.dll";
#else
    const char* sick_scan_api_lib = "libsick_scan_xd_shared_lib.so";
#endif
  signal(SIGINT, sigint_handler);
  SickScanApiLoadLibrary(sick_scan_api_lib);
  int argcs=4;
  char* args[] = { "E:/work/jyc/code/sick_scan_ws/build/Release/minimum_sick_scan_api_client.exe", "E:/work/jyc/code/sick_scan_ws/sick_scan_xd/launch/sick_multiscan.launch", "hostname:=192.168.0.237", "udp_receiver_ip:=192.168.0.236"};
  SickScanApiHandle apiHandle = SickScanApiCreate(argcs, args);
  SickScanApiInitByCli(apiHandle, argcs, args);
  apiHandle1=apiHandle;
  std::thread t1(fun);
  SickScanApiRegisterCartesianPointCloudMsg(apiHandle, &customizedPointCloudMsgCb);
  // t1.detach();
  t1.join();
  // std::this_thread::sleep_for(std::chrono::seconds(15));
  // Close lidar and release sick_scan api
  SickScanApiDeregisterCartesianPointCloudMsg(apiHandle, &customizedPointCloudMsgCb);
  SickScanApiClose(apiHandle);
  SickScanApiRelease(apiHandle);
  SickScanApiUnloadLibrary();
}
catch(const std::exception& e) {
    std::cerr << "Exception caught: " << e.what() << std::endl;
}
}
rostest commented 8 months ago

@treeandcat You are welcome! Thank you very much for your kind feedback.