rsdriver.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333
  1. #include "rsdriver.h"
  2. #define RS_Grabber_toRadians(x) ((x)*M_PI / 180.0)
  3. extern char gstr_memname[256];
  4. namespace lidar {
  5. char gstr_hostip[256];
  6. char gstr_port[256];
  7. bool g_rs_m1_run =false;
  8. bool g_rs_m1_running = false;
  9. bool g_brs_m1_Proc_running = false;
  10. int index;
  11. uint32_t point_index;
  12. rsM1_Buf *rs_m1_buf;
  13. char * g_RawData_Buf;
  14. int gnRawPos = 0;
  15. int g_seq = 0;
  16. int g_pcl =0;
  17. float pitch_rate;
  18. int pitch_max;
  19. int skip_block;
  20. float yaw_rate;
  21. float distance_max_thd;
  22. float distance_min_thd;
  23. std::vector<float> tan_lookup_table;
  24. std::thread * g_prsm1Thread;
  25. std::thread * g_prsm1ProcThread;
  26. QTime gTime;
  27. void *g_lidar_pc;
  28. static const int MEMS_BLOCKS_PER_PACKET =25;
  29. static const int MEMS_SCANS_PER_FIRING = 6;
  30. static const int POINT_COUNT_PER_VIEWFIELD = 15750;
  31. static const float ANGLE_RESOLUTION = 0.01f;
  32. static const float DISTANCE_RESOLUTION = 0.01f;
  33. int last_bag_index = -1;
  34. int last_pitch_index = 0;
  35. static float channel_cor[6] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; // distance correction offset
  36. static float channel_pitch_offset[6] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; // pitch offset
  37. static float channel_yaw_offset[6] = {0.0f, 0.0f, 0.0f, 0.0f, 0.0f, 0.0f}; //yaw offset
  38. Eigen::Matrix<float, 3, 5> input_ref_;
  39. Eigen::Matrix<float, 3, 3> rotate_gal_;
  40. void loadParam(){
  41. input_ref_<< 0.748956, 0.414693, -0.414693, -0.748956, 0,
  42. 0.33131, 0.454981, 0.454981, 0.33131, 0.5,
  43. -0.573846,-0.78805, -0.78805, -0.573846,-0.866025;
  44. rotate_gal_<< 1, 0, 0, 0, 0.965926, -0.258819, 0, 0.258819, 0.965926;
  45. pitch_rate = 1.0f;
  46. yaw_rate = 1.0f;
  47. distance_max_thd = 200.0;
  48. distance_min_thd = 0.0;
  49. pitch_max = 25000;
  50. skip_block = 0;
  51. point_index = 0;
  52. tan_lookup_table.resize(2000);
  53. for(int i = -1000; i<1000; i++)
  54. {
  55. double rad =RS_Grabber_toRadians(i/100.0f);
  56. tan_lookup_table[i+1000] = std::tan(rad);
  57. }
  58. }
  59. inline float pixlToDistance(int distance, int dsr){
  60. float result;
  61. int cor = channel_cor[dsr];
  62. if(distance <= cor)
  63. {
  64. result = 0.0;
  65. }else{
  66. result = distance -cor;
  67. }
  68. return result;
  69. }
  70. inline float yawToDeg(int deg){
  71. float result_f;
  72. float deg_f =deg;
  73. result_f = (deg_f * (1350.0f / 65534.0f) - 675.0f);
  74. return result_f;
  75. }
  76. inline float pitchToDeg(int deg){
  77. float result_f;
  78. float deg_f = deg;
  79. result_f = (deg_f * (1250.0f / pitch_max ) - 625.0f);
  80. return result_f;
  81. }
  82. inline void processrs_M1_Data(QByteArray ba)
  83. {
  84. unsigned char * pdata;
  85. float fa,fb;
  86. pdata = reinterpret_cast<unsigned char*>(ba.data());
  87. ++index;
  88. if(ba.length() != 1400 && pdata[0] != 0x55 && pdata[0] != 0xa5)
  89. {
  90. std::cout<<"No right packets!"<<std::endl;
  91. }else {
  92. if(!((int)(pdata[4]*256 +pdata[5]) < (POINT_COUNT_PER_VIEWFIELD/MEMS_BLOCKS_PER_PACKET)))
  93. {
  94. memcpy(g_RawData_Buf+gnRawPos,pdata,1400);
  95. gnRawPos= gnRawPos+1400;
  96. rs_m1_buf->WriteData(g_RawData_Buf,gnRawPos);
  97. gnRawPos = 0;
  98. index = 0;
  99. }else {
  100. if((gnRawPos+1400)<= BK32_DATA_BUFSIZE)
  101. {
  102. memcpy(g_RawData_Buf+gnRawPos,pdata,1400);
  103. gnRawPos= gnRawPos+1400;
  104. }
  105. else
  106. {
  107. std::cout<<"lidar_rsM1 processrs_M1_Data data is very big gnRawPos = "<<gnRawPos<<std::endl;
  108. }
  109. }
  110. }
  111. }
  112. void getPacket(int n){
  113. gTime.start();
  114. QUdpSocket * udpSocket = new QUdpSocket( );
  115. bool bbind = udpSocket->bind(QHostAddress(gstr_hostip), atoi(gstr_port));
  116. int i = 0;
  117. while(g_rs_m1_run)
  118. {
  119. if(udpSocket->hasPendingDatagrams())
  120. {
  121. QNetworkDatagram datagram = udpSocket->receiveDatagram();
  122. processrs_M1_Data(datagram.data());
  123. datagram.clear();
  124. }
  125. else
  126. {
  127. std::this_thread::sleep_for(std::chrono::microseconds(50));
  128. // std::this_thread::sleep_for(std::chrono::milliseconds(1));
  129. }
  130. }
  131. udpSocket->close();
  132. delete udpSocket;
  133. g_rs_m1_running = false;
  134. }
  135. void process_rs_M1_obs(char * strdata,int nLen)
  136. {
  137. loadParam();
  138. float pitch;
  139. float yaw;
  140. int bag = 0;
  141. int block = 0;
  142. int channel = 0;
  143. int buf1len = nLen/1400;
  144. // std::cout<<" len :"<<nLen<<"ooooooooooooooo"<<buf1len<<std::endl;
  145. QDateTime dt = QDateTime::currentDateTime();
  146. pcl::PointCloud<pcl::PointXYZI>::Ptr point_cloud(
  147. new pcl::PointCloud<pcl::PointXYZI>());
  148. pcl::PointXYZI point;
  149. point_cloud->header.frame_id = "velodyne";
  150. point_cloud->height = 5;
  151. point_cloud->header.stamp = dt.currentMSecsSinceEpoch();
  152. point_cloud->width = 15750;
  153. // point_cloud->is_dense = false;
  154. point_cloud->resize(point_cloud->height*point_cloud->width);
  155. unsigned char * pstr = (unsigned char *)strdata;
  156. // std::cout<<"len is "<<buf1len<<std::endl;
  157. for ( bag = 0; bag < buf1len; bag++)
  158. {
  159. int bag_index = (pstr[bag*1400 +4]*256 + pstr[bag*1400 + 5]);
  160. if(bag_index - last_bag_index > 1 && (bag_index - last_bag_index) < POINT_COUNT_PER_VIEWFIELD / MEMS_BLOCKS_PER_PACKET
  161. && last_bag_index != -1)
  162. {
  163. int lose_bag_count = bag_index - last_bag_index - 1;
  164. while(lose_bag_count --)
  165. {
  166. for(block = 0; block < MEMS_BLOCKS_PER_PACKET; block++)
  167. {
  168. for (channel = 1; channel <MEMS_SCANS_PER_FIRING; channel++){
  169. point.y = NAN;
  170. point.x = NAN;
  171. point.z = NAN;
  172. point.intensity = 0;
  173. point_cloud->at(point_index, channel - 1) = point;
  174. // point_cloud->push_back(point);
  175. // ++point_cloud->width;
  176. }
  177. point_index++;
  178. }
  179. }
  180. }
  181. for (block = skip_block; block < MEMS_BLOCKS_PER_PACKET; block++)
  182. {
  183. int pitch_t = ((pstr[bag*1400+20 + block * 52] *256) + pstr[bag*1400 + 21 + block * 52]) ;
  184. if(last_pitch_index > pitch_t){
  185. if(last_bag_index = POINT_COUNT_PER_VIEWFIELD / MEMS_BLOCKS_PER_PACKET){
  186. pitch_max = last_pitch_index;
  187. }
  188. point_index= 0;
  189. // point_cloud->width = 0;
  190. skip_block = block;
  191. last_pitch_index = pitch_t;
  192. break;
  193. }
  194. last_pitch_index = pitch_t;
  195. pitch = pitchToDeg(pitch_t) * ANGLE_RESOLUTION;
  196. int yaw_t = ((pstr[bag*1400 +22 + block * 52] *256) + pstr[bag*1400 + 23 + block * 52]) ;
  197. yaw = yawToDeg(yaw_t) * ANGLE_RESOLUTION;
  198. Eigen::Matrix<float, 3, 1> n_gal;
  199. Eigen::Matrix<float, 3, 1> i_out;
  200. for (channel = 0; channel <(MEMS_SCANS_PER_FIRING-1); channel++){
  201. int ax, ay;
  202. float tanax, tanay;
  203. ax = (int)(100 * pitch_rate * (pitch + channel_pitch_offset[channel+1]));
  204. ay = (int)(100 * yaw_rate * (yaw + channel_yaw_offset[channel+1]));
  205. tanax = tan_lookup_table[ax + 1000];
  206. tanay = tan_lookup_table[ay + 1000];
  207. tanax = -tanax;
  208. tanay = -tanay;
  209. n_gal << tanay, -tanax, 1;
  210. n_gal.normalize();
  211. n_gal = rotate_gal_ * n_gal;
  212. i_out = input_ref_.col(channel ) - 2 * n_gal * n_gal.transpose() * input_ref_.col(channel);
  213. int Range_t = ((pstr[bag*1400 + block * 52 + 34 + 8 * channel] << 8) + pstr[bag*1400+block * 52 + 35 + 8 * channel]);
  214. float Range=pixlToDistance(Range_t,(channel+1)) *DISTANCE_RESOLUTION ;
  215. unsigned char intensity = ((pstr[bag*1400 + block * 52 + 32 + 8 * channel] << 8)
  216. + pstr[bag*1400 + block* 52 + 33 + 8 * channel]);
  217. if(Range > distance_max_thd || Range < distance_min_thd)
  218. {
  219. point.y = NAN;
  220. point.x = NAN;
  221. point.z = NAN;
  222. point.intensity = 0;
  223. // point_cloud->push_back(point);
  224. // ++point_cloud->width;
  225. }else {
  226. point.y = i_out(2) * Range;
  227. point.x = -i_out(0) * Range;
  228. point.z = i_out(1) * Range;
  229. point.intensity = intensity;
  230. // point_cloud->push_back(point);
  231. // ++point_cloud->width;
  232. // std::cout<<" x y z "<<point.x<<" , "<<point.y<<" , "<<point.z<< " , "<<Range<<std::endl;
  233. }
  234. if(point_index < POINT_COUNT_PER_VIEWFIELD){
  235. point_cloud->at(point_index, channel) = point;
  236. // point_cloud->push_back(point);
  237. // ++point_cloud->width;
  238. }
  239. }
  240. point_index++;
  241. skip_block = 0;
  242. }
  243. last_bag_index = bag_index;
  244. }
  245. // std::cout<<"point size is "<<point_cloud->width<<std::endl;
  246. char * strOut = new char[4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->size()* sizeof(pcl::PointXYZI)];
  247. int * pHeadSize = (int *)strOut;
  248. *pHeadSize = 4 + point_cloud->header.frame_id.size()+4+8;
  249. memcpy(strOut+4,point_cloud->header.frame_id.c_str(),point_cloud->header.frame_id.size());
  250. pcl::uint32_t * pu32 = (pcl::uint32_t *)(strOut+4+sizeof(point_cloud->header.frame_id.size()));
  251. *pu32 = point_cloud->header.seq;
  252. memcpy(strOut+4+sizeof(point_cloud->header.frame_id.size()) + 4,&point_cloud->header.stamp,8);
  253. pcl::PointXYZI * p;
  254. p = (pcl::PointXYZI *)(strOut +4+sizeof(point_cloud->header.frame_id.size()) + 4+8 );
  255. memcpy(p,point_cloud->points.data(),point_cloud->size() * sizeof(pcl::PointXYZI));
  256. iv::modulecomm::ModuleSendMsg(g_lidar_pc,strOut,4+sizeof(point_cloud->header.frame_id.size()) + 4+8+point_cloud->size() * sizeof(pcl::PointXYZI));
  257. delete strOut;
  258. }
  259. void rsm1_Proc_Func(int n)
  260. {
  261. std::cout<<"Enter rsM1_Proc_Func"<<std::endl;
  262. char * strdata = new char[BK32_DATA_BUFSIZE];
  263. int nIndex;
  264. int nRead;
  265. while(g_rs_m1_run)
  266. {
  267. if((nRead = rs_m1_buf->ReadData(strdata,BK32_DATA_BUFSIZE,&nIndex))>0)
  268. {
  269. process_rs_M1_obs(strdata,nRead);
  270. }
  271. else
  272. {
  273. std::this_thread::sleep_for(std::chrono::milliseconds(1));
  274. }
  275. }
  276. g_rs_m1_running = false;
  277. std::cout<<"Exit rsm1_Proc_Func"<<std::endl;
  278. }
  279. int StartLidar_rs_m1()
  280. {
  281. std::cout<<"Now Start rsm1 Listen."<<std::endl;
  282. g_RawData_Buf = new char[BK32_DATA_BUFSIZE];
  283. rs_m1_buf = new rsM1_Buf();
  284. g_rs_m1_run = true;
  285. g_rs_m1_running = true;
  286. g_brs_m1_Proc_running = true;
  287. g_lidar_pc = iv::modulecomm::RegisterSend(gstr_memname,20000000,1);
  288. g_prsm1Thread = new std::thread(getPacket,0);
  289. g_prsm1ProcThread = new std::thread(rsm1_Proc_Func,0);
  290. return 0;
  291. }
  292. void StopLidar_rs16()
  293. {
  294. std::cout<<"Now Close rsm1. "<<std::endl;
  295. g_rs_m1_run = false;
  296. g_prsm1Thread->join();
  297. g_prsm1ProcThread->join();
  298. delete g_prsm1ProcThread;
  299. delete g_prsm1Thread;
  300. delete rs_m1_buf;
  301. delete g_RawData_Buf;
  302. }
  303. }