Ver código fonte

add adapi_driver_lidar_python for get pointcloud use python.

yuchuli 8 meses atrás
pai
commit
dcd17de41b

+ 91 - 0
src/api/adapi_driver_lidar_python/PyModuleCommModule.py

@@ -0,0 +1,91 @@
+
+import threading  
+import time  
+
+import modulecommpython
+import numpy as np  
+
+
+modulelock = threading.Lock()  
+nThread = 0
+  
+class PyModuleComm:  
+    def __init__(self,strname):  
+        # 初始化代码...  
+        print("name: ",strname)
+        self.strmemname = strname
+        self.mbRegister = False
+        global nThread
+        nThread = nThread+1
+        self.mnMode = 0
+        print("nThread = ",nThread)
+        self.obj = modulecommpython.get_ca_object()
+        pass  
+
+    def RegisterRecv(self,call):
+        if self.mbRegister:
+            print(" Have register, can't register other.")
+            return
+        print("Register: ",self.strmemname)
+        self.mpcall = call
+        self.mbRegister = True
+        self.mbRun = True
+        self.mpthread = threading.Thread(target=self.threadrecvdata, args=(self.strmemname,))  
+        self.mpthread.start()
+        print("complete create thread.")
+        self.mnMode = 1
+        self.obj.RegisterRecv(self.strmemname)
+
+    def RegiseterSend(self,nSize,nPacCount):
+        if self.mbRegister:
+            print(" Have register, can't register other.")
+            return
+        print("Register: ",self.strmemname)
+        self.mnsize = nSize
+        self.mnPacCount = nPacCount
+        self.mbRegister = True
+        self.mnMode = 2
+        self.obj.RegisterSend(self.strmemname,nSize,nPacCount)
+    
+    def SendData(self,arr,nsendsize):      
+    #    nrealsize = np.zeros(1, dtype=np.int32)  
+        nrtn = self.obj.SendData(arr,nsendsize)
+  
+    def threadrecvdata(self, arg):  
+        # 这个函数将被线程执行  
+ #       print(f"线程开始执行,参数是 {arg}")  
+        nBuffSize = int(1000)
+        arr = np.zeros(nBuffSize,dtype=np.int8)
+        recvtime = np.zeros(1,dtype=np.int64)
+        nrealsize = np.zeros(1,dtype=np.int32)
+        while 1:
+            nrtn = self.obj.RecvData(arr,nBuffSize,nrealsize,recvtime)
+            if nrtn > 0:
+                self.mpcall(arr,nrtn,recvtime)
+            else:
+                pass
+            if nrtn < 0:
+                nBuffSize = int(nrealsize[0] * 2)
+                arr = np.zeros(nBuffSize,dtype=np.int8)
+            else:
+                time.sleep(0.001)
+            
+        print("threadrecvdata complete.")
+
+    def stop_thread(self):
+        self.mbRun = False
+        self.mpthread.join()
+  
+    def start_thread(self, arg):  
+        # 创建线程对象,target参数指向要在线程中运行的函数  
+        self.mbRun = True
+        self.mpthread = threading.Thread(target=self.my_function, args=(arg,))  
+          
+        # 启动线程  
+        self.mpthread.start()  
+          
+        # 可以在这里添加其他代码,主线程会继续执行  
+        print("主线程继续执行...")  
+  
+        # 如果需要等待线程结束,可以调用 join() 方法  
+        # thread.join()  

+ 1 - 0
src/api/adapi_driver_lidar_python/Readme.md

@@ -0,0 +1 @@
+pip3 install open3d

+ 49 - 0
src/api/adapi_driver_lidar_python/pythonlidarpc.py

@@ -0,0 +1,49 @@
+import modulecommpython
+import numpy as np  
+import time
+import sys  
+import open3d as o3d
+
+from PyModuleCommModule import PyModuleComm
+
+def lidarpc_callback(arr : np,nsize,time):  
+    sub_arr = arr[0:nsize]
+    databytes = sub_arr.tobytes()
+    int_array = np.frombuffer(databytes, dtype='<i4')
+    point_bytes = databytes[int_array[0]:]
+    num_floats = len(point_bytes) // 4
+    if num_floats % 8 == 0:
+        N = num_floats // 8
+        print("Point Cloud point size: ",N)
+        float_array = np.frombuffer(point_bytes[:num_floats*4], dtype='<f4').reshape((N, 8))
+        # 提取坐标和反射率
+        points = float_array[:, 0:3]  # 取前三个列作为坐标
+     #   print(points)
+        reflectances = float_array[:, 3]  # 取最后一个列作为反射率(虽然Open3D不直接显示它)
+        # 创建Open3D点云对象
+        pcd = o3d.geometry.PointCloud()
+        pcd.points = o3d.utility.Vector3dVector(points)
+        # 可视化点云(注意:反射率信息不会被直接显示,但你可以后续处理它)
+     #   o3d.visualization.draw_geometries([pcd])
+    else:
+        print("Point Cloud incomplete.")
+
+def main():  
+    # 初始化一个变量  
+    count = 0
+    count = 3.5/1.5
+    count = int(count)
+    print("count = ",count)  
+
+    mc = PyModuleComm("lidar_pc")
+    mc.RegisterRecv(lidarpc_callback)
+
+    # 使用while循环,只要count小于10,就继续循环  
+    while count < 10:
+        time.sleep(0.05)
+
+    print("循环结束!")  
+  
+# 调用main函数  
+if __name__ == "__main__":  
+    main()

+ 3 - 1
src/detection/detection_lidar_transfusion/main.cpp

@@ -31,13 +31,15 @@ void LoadBin(pcl::PointCloud<pcl::PointXYZI>::Ptr & point_cloud,std::string strp
         xFile.read((char *)&i,sizeof(float));
  //       xFile.read((char *)&ring,sizeof(float));
  //       std::cout<<x<<" "<<y<<" "<<z<<" "<<i<<std::endl;
-        xp.x = x; xp.y = y; xp.z = z; xp.intensity = i;
+        xp.x = x; xp.y = y; xp.z = z; xp.intensity = i ;
         std::cout<<" x: "<<xp.x<<" y:"<<xp.y<<" z:"<<xp.z<<" int:"<<xp.intensity<<" ring:"<<ring<<std::endl;
         point_cloud->points.push_back(xp);++point_cloud->width;
         }
     }
     xFile.close();
 
+//    pcl::io::savePCDFile("/home/nvidia/kittypcd.pcd",*point_cloud);
+
 }
 
 void testdet(std::string & path)

+ 16 - 7
src/detection/detection_lidar_transfusion/preprocess/preprocess_kernel.cu

@@ -190,17 +190,26 @@ __global__ void generateSweepPoints_kernel(
 
   float input_intensity = static_cast<float>(input_data[point_idx * input_point_step + 12]);
 
+//  output_points[point_idx * num_features] =
+//    transform_array[0] * input_x.value + transform_array[4] * input_y.value +
+//    transform_array[8] * input_z.value + transform_array[12];
+//  output_points[point_idx * num_features + 1] =
+//    transform_array[1] * input_x.value + transform_array[5] * input_y.value +
+//    transform_array[9] * input_z.value + transform_array[13];
+//  output_points[point_idx * num_features + 2] =
+//    transform_array[2] * input_x.value + transform_array[6] * input_y.value +
+//    transform_array[10] * input_z.value + transform_array[14];
+//  output_points[point_idx * num_features + 3] = input_intensity;
+//  output_points[point_idx * num_features + 4] = time_lag;
+
   output_points[point_idx * num_features] =
-    transform_array[0] * input_x.value + transform_array[4] * input_y.value +
-    transform_array[8] * input_z.value + transform_array[12];
+    input_x.value ;
   output_points[point_idx * num_features + 1] =
-    transform_array[1] * input_x.value + transform_array[5] * input_y.value +
-    transform_array[9] * input_z.value + transform_array[13];
+    input_y.value ;
   output_points[point_idx * num_features + 2] =
-    transform_array[2] * input_x.value + transform_array[6] * input_y.value +
-    transform_array[10] * input_z.value + transform_array[14];
+    input_z.value;
   output_points[point_idx * num_features + 3] = input_intensity;
-  output_points[point_idx * num_features + 4] = time_lag;
+  output_points[point_idx * num_features + 4] = 0;
 }
 
 cudaError_t PreprocessCuda::generateSweepPoints_launch(