main.cpp 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293
  1. #include <csignal>
  2. #include "lio/Estimator.h"
  3. #include "lio/mapper.h"
  4. #include "lddc.h"
  5. #include "lds_hub.h"
  6. #include "lds_lidar.h"
  7. #include "lds_lvx.h"
  8. #include "livox_sdk.h"
  9. #include "pangolinViewer.h"
  10. #include "segment/LidarFeatureExtractor.h"
  11. #include "define/timedlockdata.hpp"
  12. //雷达相关
  13. livox_ros::Lddc *lddc= nullptr;
  14. //特征提取相关
  15. LidarFeatureExtractor* lidarFeatureExtractor;
  16. pcl::PointCloud<PointType>::Ptr laserCloud;
  17. int Lidar_Type=0;
  18. int N_SCANS = 6;
  19. bool Feature_Mode = false;
  20. bool Use_seg = false;
  21. //slam 地图相关
  22. Mapper* pMaper= nullptr;
  23. TimedLockData<PointCloud> scan_cloud;
  24. TimedLockData<PointCloud::Ptr> localmap_cloud;
  25. TimedLockData<Eigen::Matrix4d> cur_pose;
  26. double final_cost=0;
  27. void CloudFullCallback(pcl::PointCloud<PointType>::Ptr cloud,double timebase)
  28. {
  29. scan_cloud.reset(*cloud,0.1);
  30. }
  31. void CloudLocalCallback(pcl::PointCloud<PointType>::Ptr cloud,double timebase)
  32. {
  33. localmap_cloud.reset(cloud,0.1);
  34. }
  35. void OdometryCallback(Eigen::Matrix4d tranform,double timebase)
  36. {
  37. cur_pose.reset(tranform);
  38. }
  39. void FinalCostCallback(double cost)
  40. {
  41. final_cost=cost;
  42. }
  43. void CloudCallback(TimeCloud tc,int handle)
  44. {
  45. double timeSpan =tc.cloud->points.back().normal_x;
  46. laserCloud.reset(new pcl::PointCloud<PointType>);
  47. laserCloud->reserve(15000*N_SCANS);
  48. PointType point;
  49. for(const auto& p : tc.cloud->points)
  50. {
  51. //std::cout<<point.normal_y<<" "<<point.normal_x<<" "<<timeSpan<<std::endl;
  52. if (p.normal_y > N_SCANS - 1) continue;
  53. if (p.x < 0.01) continue;
  54. if (!pcl_isfinite(p.x) ||
  55. !pcl_isfinite(p.y) ||
  56. !pcl_isfinite(p.z))
  57. {
  58. continue;
  59. }
  60. point.x=p.x;
  61. point.y=p.y;
  62. point.z=p.z;
  63. point.normal_x = p.normal_x / timeSpan; //normao_x time
  64. point.intensity=p.intensity;
  65. int line=int(p.normal_y);
  66. point.normal_y=LidarFeatureExtractor::_int_as_float(line);
  67. laserCloud->push_back(point);
  68. /*std::cout<<" x:"<<point.x<<" y:"<<point.y<<" z:"<<point.z
  69. <<" intnesity:"<<point.intensity<<" normal_x:"<<point.normal_x
  70. <<" normal_y:"<<point.normal_y<<std::endl;*/
  71. }
  72. tc.cloud=laserCloud;
  73. pMaper->AddCloud(tc);
  74. }
  75. void ImuDataCallback(ImuData imu,int handle){
  76. pMaper->AddImu(imu);
  77. }
  78. bool InitLidar(double freq);
  79. bool InitMap(std::string config_file);
  80. void pangolinSpinOnce(PangolinViewer* viewer)
  81. {
  82. if(cur_pose.timeout()==false)
  83. viewer->ShowRealtimePose(cur_pose.Get());
  84. //绘制变换后的扫描点
  85. double ptSize=1;
  86. double alpha=1;
  87. PointCloud scan=scan_cloud.Get();
  88. if(scan.size()>0)
  89. viewer->DrawCloud(scan.makeShared(),1,1,1,alpha,ptSize);
  90. //地图点
  91. ptSize=0.1;
  92. alpha=0.2;
  93. viewer->DrawCloud(pMaper->GetMapCorner(),1,0,0,alpha,ptSize);
  94. viewer->DrawCloud(pMaper->GetMapSurf(),0.1,1,0,alpha,ptSize);
  95. viewer->DrawCloud(pMaper->GetMapNonf(),0.1,0,1,alpha,ptSize);
  96. viewer->ShowSlamCost(final_cost);
  97. if(pMaper!= nullptr)
  98. viewer->ShowSlamQueueTime(pMaper->_lidarMsgQueue.size(),pMaper->frame_tm_);
  99. }
  100. void OnStartBtn(std::string lvxfile)
  101. {
  102. if(lddc!= nullptr)
  103. {
  104. if (lvxfile=="")
  105. lddc->Start();
  106. else
  107. lddc->Start(lvxfile);
  108. }
  109. }
  110. void OnStopBtn()
  111. {
  112. if(lddc!= nullptr)
  113. lddc->Stop();
  114. }
  115. void OnFreqChanged(int freq)
  116. {
  117. if(lddc!= nullptr)
  118. lddc->SetPublishFrq(freq);
  119. }
  120. int main(int argc, char** argv)
  121. {
  122. //reg参数
  123. std::string config_file="../config/horizon_config.yaml";
  124. if(InitMap(config_file)==false)
  125. return -1;
  126. //初始化雷达
  127. double publish_freq = 10.0;
  128. if(!InitLidar(publish_freq))
  129. return -3;
  130. PangolinViewer* viewer=PangolinViewer::CreateViewer();
  131. viewer->SetCallbacks(pangolinSpinOnce,OnStartBtn,OnStopBtn,OnFreqChanged);
  132. viewer->Join();
  133. TimerRecord::PrintAll();
  134. lddc->Stop();
  135. pMaper->completed();
  136. delete lidarFeatureExtractor;
  137. delete pMaper;
  138. delete lddc;
  139. delete viewer;
  140. return 0;
  141. }
  142. bool InitMap(std::string config_file)
  143. {
  144. cv::FileStorage fsSettings(config_file, cv::FileStorage::READ);
  145. if (!fsSettings.isOpened())
  146. {
  147. std::cout << "config_file error: cannot open " << config_file << std::endl;
  148. return false;
  149. }
  150. Lidar_Type = static_cast<int>(fsSettings["Lidar_Type"]);
  151. N_SCANS = static_cast<int>(fsSettings["Used_Line"]);
  152. Feature_Mode = static_cast<int>(fsSettings["Feature_Mode"]);
  153. Use_seg = static_cast<int>(fsSettings["Use_seg"]);
  154. int NumCurvSize = static_cast<int>(fsSettings["NumCurvSize"]);
  155. float DistanceFaraway = static_cast<float>(fsSettings["DistanceFaraway"]);
  156. int NumFlat = static_cast<int>(fsSettings["NumFlat"]);
  157. int PartNum = static_cast<int>(fsSettings["PartNum"]);
  158. float FlatThreshold = static_cast<float>(fsSettings["FlatThreshold"]);
  159. float BreakCornerDis = static_cast<float>(fsSettings["BreakCornerDis"]);
  160. float LidarNearestDis = static_cast<float>(fsSettings["LidarNearestDis"]);
  161. float KdTreeCornerOutlierDis = static_cast<float>(fsSettings["KdTreeCornerOutlierDis"]);
  162. int ivox_nearby_type = static_cast<int>(fsSettings["ivox_nearby_type"]);
  163. int max_ivox_node = static_cast<int>(fsSettings["max_ivox_node"]);
  164. float ivox_resolution = static_cast<float>(fsSettings["ivox_node_solution"]);
  165. std::string map_file=static_cast<string>(fsSettings["map_file"]);
  166. laserCloud.reset(new pcl::PointCloud<PointType>);
  167. lidarFeatureExtractor = new LidarFeatureExtractor(N_SCANS,
  168. NumCurvSize,
  169. DistanceFaraway,
  170. NumFlat,
  171. PartNum,
  172. FlatThreshold,
  173. BreakCornerDis,
  174. LidarNearestDis,
  175. KdTreeCornerOutlierDis);
  176. //map 参数
  177. float filter_parameter_corner = 0.2;
  178. float filter_parameter_surf = 0.4;
  179. int IMU_Mode = 2;
  180. double vecTlb[]={1.0, 0.0, 0.0, -0.05512,
  181. 0.0, 1.0, 0.0, -0.02226,
  182. 0.0, 0.0, 1.0, 0.0297,
  183. 0.0, 0.0, 0.0, 1.0};
  184. // set extrinsic matrix between lidar & IMU
  185. Eigen::Matrix3d R;
  186. Eigen::Vector3d t;
  187. R << vecTlb[0], vecTlb[1], vecTlb[2],
  188. vecTlb[4], vecTlb[5], vecTlb[6],
  189. vecTlb[8], vecTlb[9], vecTlb[10];
  190. t << vecTlb[3], vecTlb[7], vecTlb[11];
  191. Eigen::Quaterniond qr(R);
  192. R = qr.normalized().toRotationMatrix();
  193. int WINDOWSIZE = 0;
  194. if (IMU_Mode < 2)
  195. WINDOWSIZE = 1;
  196. else
  197. WINDOWSIZE = 20;
  198. pMaper = new Mapper(WINDOWSIZE, lidarFeatureExtractor,Use_seg,filter_parameter_corner, filter_parameter_surf,
  199. ivox_nearby_type, max_ivox_node, ivox_resolution);
  200. pMaper->InitRT(R, t);
  201. pMaper->SetOdomCallback(OdometryCallback);
  202. pMaper->SetCloudMappedCallback(CloudFullCallback);
  203. pMaper->SetLocalMapCloudCallback(CloudLocalCallback);
  204. pMaper->SetFinalCostCallback(FinalCostCallback);
  205. printf("slam map file:%s\n",map_file.c_str());
  206. pMaper->LoadMap(map_file);
  207. double RPI = M_PI / 180.0;
  208. Eigen::Vector3d eulerAngle(0 * RPI, 0 * RPI, 11.5* RPI);
  209. Eigen::AngleAxisd rollAngle(Eigen::AngleAxisd(eulerAngle(0), Eigen::Vector3d::UnitX()));
  210. Eigen::AngleAxisd pitchAngle(Eigen::AngleAxisd(eulerAngle(1), Eigen::Vector3d::UnitY()));
  211. Eigen::AngleAxisd yawAngle(Eigen::AngleAxisd(eulerAngle(2), Eigen::Vector3d::UnitZ()));
  212. Eigen::Matrix3d rotation_matrix;
  213. rotation_matrix = yawAngle * pitchAngle * rollAngle;
  214. Eigen::Matrix4d transform;
  215. transform.topLeftCorner(3, 3) = rotation_matrix;
  216. transform.topRightCorner(3, 1) = Eigen::Vector3d(0.46, 0.48, 0.73);
  217. pMaper->SetInitPose(transform);
  218. printf(" window size :%d\n--------------", WINDOWSIZE);
  219. return true;
  220. }
  221. bool InitLidar(double publish_freq)
  222. {
  223. LivoxSdkVersion _sdkversion;
  224. GetLivoxSdkVersion(&_sdkversion);
  225. const int32_t kSdkVersionMajorLimit = 2;
  226. if (_sdkversion.major < kSdkVersionMajorLimit) {
  227. printf("The SDK version[%d.%d.%d] is too low\n", _sdkversion.major,
  228. _sdkversion.minor, _sdkversion.patch);
  229. return false;
  230. }
  231. if (publish_freq > 100.0) {
  232. publish_freq = 100.0;
  233. } else if (publish_freq < 0.1) {
  234. publish_freq = 0.1;
  235. } else {
  236. publish_freq = publish_freq;
  237. }
  238. lddc= new livox_ros::Lddc(publish_freq);
  239. lddc->SetCloudCallback(CloudCallback);
  240. lddc->SetImuCallback(ImuDataCallback);
  241. return true;
  242. }