utility.h 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341
  1. #pragma once
  2. #ifndef _UTILITY_LIDAR_ODOMETRY_H_
  3. #define _UTILITY_LIDAR_ODOMETRY_H_
  4. #include <ros/ros.h>
  5. #include <std_msgs/Header.h>
  6. #include <std_msgs/Float64MultiArray.h>
  7. #include <sensor_msgs/Imu.h>
  8. #include <sensor_msgs/PointCloud2.h>
  9. #include <sensor_msgs/NavSatFix.h>
  10. #include <nav_msgs/Odometry.h>
  11. #include <nav_msgs/Path.h>
  12. #include <visualization_msgs/Marker.h>
  13. #include <visualization_msgs/MarkerArray.h>
  14. #include <opencv2/opencv.hpp>
  15. #include <pcl/point_cloud.h>
  16. #include <pcl/point_types.h>
  17. #include <pcl/search/impl/search.hpp>
  18. #include <pcl/range_image/range_image.h>
  19. #include <pcl/kdtree/kdtree_flann.h>
  20. #include <pcl/common/common.h>
  21. #include <pcl/common/transforms.h>
  22. #include <pcl/registration/icp.h>
  23. #include <pcl/io/pcd_io.h>
  24. #include <pcl/filters/filter.h>
  25. #include <pcl/filters/voxel_grid.h>
  26. #include <pcl/filters/crop_box.h>
  27. #include <pcl_conversions/pcl_conversions.h>
  28. #include <tf/LinearMath/Quaternion.h>
  29. #include <tf/transform_listener.h>
  30. #include <tf/transform_datatypes.h>
  31. #include <tf/transform_broadcaster.h>
  32. #include <tf/transform_broadcaster.h>
  33. #include <vector>
  34. #include <cmath>
  35. #include <algorithm>
  36. #include <queue>
  37. #include <deque>
  38. #include <iostream>
  39. #include <fstream>
  40. #include <ctime>
  41. #include <cfloat>
  42. #include <iterator>
  43. #include <sstream>
  44. #include <string>
  45. #include <limits>
  46. #include <iomanip>
  47. #include <array>
  48. #include <thread>
  49. #include <mutex>
  50. using namespace std;
  51. typedef pcl::PointXYZI PointType;
  52. class ParamServer
  53. {
  54. public:
  55. ros::NodeHandle nh;
  56. std::string robot_id;
  57. //Topics
  58. string pointCloudTopic;
  59. string imuTopic;
  60. string odomTopic;
  61. string gpsTopic;
  62. //Frames
  63. string lidarFrame;
  64. string baselinkFrame;
  65. string odometryFrame;
  66. string mapFrame;
  67. string mapPath;
  68. bool useRing;
  69. bool useOdom;
  70. // GPS Settings
  71. bool useImuHeadingInitialization;
  72. bool useGpsElevation;
  73. float gpsCovThreshold;
  74. float poseCovThreshold;
  75. // Save pcd
  76. bool savePCD;
  77. bool saveJson;
  78. string savePCDDirectory;
  79. // Velodyne Sensor Configuration: Velodyne
  80. int N_SCAN;
  81. int Horizon_SCAN;
  82. string timeField;
  83. int downsampleRate;
  84. float lidarMinRange;
  85. float lidarMaxRange;
  86. // IMU
  87. float imuAccNoise;
  88. float imuGyrNoise;
  89. float imuAccBiasN;
  90. float imuGyrBiasN;
  91. float imuGravity;
  92. float imuRPYWeight;
  93. float odomYaw;
  94. vector<double> extRotV;
  95. vector<double> extRPYV;
  96. vector<double> extTransV;
  97. Eigen::Matrix3d extRot;
  98. Eigen::Matrix3d extRPY;
  99. Eigen::Vector3d extTrans;
  100. Eigen::Quaterniond extQRPY;
  101. Eigen::AngleAxisd odomAngle;
  102. // LOAM
  103. float edgeThreshold;
  104. float surfThreshold;
  105. int edgeFeatureMinValidNum;
  106. int surfFeatureMinValidNum;
  107. // voxel filter paprams
  108. float odometrySurfLeafSize;
  109. float mappingCornerLeafSize;
  110. float mappingSurfLeafSize ;
  111. float z_tollerance;
  112. float rotation_tollerance;
  113. // CPU Params
  114. int numberOfCores;
  115. double mappingProcessInterval;
  116. // Surrounding map
  117. float surroundingkeyframeAddingDistThreshold;
  118. float surroundingkeyframeAddingAngleThreshold;
  119. float surroundingKeyframeDensity;
  120. float surroundingKeyframeSearchRadius;
  121. // Loop closure
  122. bool loopClosureEnableFlag;
  123. float loopClosureFrequency;
  124. int surroundingKeyframeSize;
  125. float historyKeyframeSearchRadius;
  126. float historyKeyframeSearchTimeDiff;
  127. int historyKeyframeSearchNum;
  128. float historyKeyframeFitnessScore;
  129. // global map visualization radius
  130. float globalMapVisualizationSearchRadius;
  131. float globalMapVisualizationPoseDensity;
  132. float globalMapVisualizationLeafSize;
  133. //Localization
  134. int addKeyFameNum{0};
  135. float ndtMinScore{0.05};
  136. ParamServer()
  137. {
  138. nh.param<std::string>("/robot_id", robot_id, "roboat");
  139. nh.param<std::string>("lio_sam/pointCloudTopic", pointCloudTopic, "points_raw");
  140. nh.param<std::string>("lio_sam/imuTopic", imuTopic, "imu_correct");
  141. nh.param<std::string>("lio_sam/odomTopic", odomTopic, "odometry/imu");
  142. nh.param<std::string>("lio_sam/gpsTopic", gpsTopic, "odometry/gps");
  143. nh.param<std::string>("lio_sam/lidarFrame", lidarFrame, "base_link");
  144. nh.param<std::string>("lio_sam/baselinkFrame", baselinkFrame, "base_link");
  145. nh.param<std::string>("lio_sam/odometryFrame", odometryFrame, "odom");
  146. nh.param<std::string>("lio_sam/mapFrame", mapFrame, "map");
  147. nh.param<std::string>("lio_sam/mapPath", mapPath, "");
  148. nh.param<bool>("lio_sam/useImuHeadingInitialization", useImuHeadingInitialization, false);
  149. nh.param<bool>("lio_sam/useRing", useRing, false);
  150. nh.param<bool>("lio_sam/useOdom", useOdom, false);
  151. nh.param<bool>("lio_sam/useGpsElevation", useGpsElevation, false);
  152. nh.param<float>("lio_sam/gpsCovThreshold", gpsCovThreshold, 2.0);
  153. nh.param<float>("lio_sam/poseCovThreshold", poseCovThreshold, 25.0);
  154. nh.param<bool>("lio_sam/savePCD", savePCD, false);
  155. nh.param<bool>("lio_sam/saveJson", saveJson, false);
  156. nh.param<std::string>("lio_sam/savePCDDirectory", savePCDDirectory, "/Downloads/LOAM/");
  157. nh.param<int>("lio_sam/N_SCAN", N_SCAN, 16);
  158. nh.param<int>("lio_sam/Horizon_SCAN", Horizon_SCAN, 1800);
  159. nh.param<std::string>("lio_sam/timeField", timeField, "time");
  160. nh.param<int>("lio_sam/downsampleRate", downsampleRate, 1);
  161. nh.param<float>("lio_sam/lidarMinRange", lidarMinRange, 1.0);
  162. nh.param<float>("lio_sam/lidarMaxRange", lidarMaxRange, 1000.0);
  163. nh.param<float>("lio_sam/imuAccNoise", imuAccNoise, 0.01);
  164. nh.param<float>("lio_sam/imuGyrNoise", imuGyrNoise, 0.001);
  165. nh.param<float>("lio_sam/imuAccBiasN", imuAccBiasN, 0.0002);
  166. nh.param<float>("lio_sam/imuGyrBiasN", imuGyrBiasN, 0.00003);
  167. nh.param<float>("lio_sam/imuGravity", imuGravity, 9.80511);
  168. nh.param<float>("lio_sam/imuRPYWeight", imuRPYWeight, 0.01);
  169. nh.param<float>("lio_sam/odomYaw", odomYaw, 0.0);
  170. nh.param<vector<double>>("lio_sam/extrinsicRot", extRotV, vector<double>());
  171. nh.param<vector<double>>("lio_sam/extrinsicRPY", extRPYV, vector<double>());
  172. nh.param<vector<double>>("lio_sam/extrinsicTrans", extTransV, vector<double>());
  173. extRot = Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(extRotV.data(), 3, 3);
  174. extRPY = Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(extRPYV.data(), 3, 3);
  175. extTrans = Eigen::Map<const Eigen::Matrix<double, -1, -1, Eigen::RowMajor>>(extTransV.data(), 3, 1);
  176. extQRPY = Eigen::Quaterniond(extRPY);
  177. odomAngle = Eigen::AngleAxisd (odomYaw, Eigen::Vector3d(0,0,1));
  178. nh.param<float>("lio_sam/edgeThreshold", edgeThreshold, 0.1);
  179. nh.param<float>("lio_sam/surfThreshold", surfThreshold, 0.1);
  180. nh.param<int>("lio_sam/edgeFeatureMinValidNum", edgeFeatureMinValidNum, 10);
  181. nh.param<int>("lio_sam/surfFeatureMinValidNum", surfFeatureMinValidNum, 100);
  182. nh.param<float>("lio_sam/odometrySurfLeafSize", odometrySurfLeafSize, 0.2);
  183. nh.param<float>("lio_sam/mappingCornerLeafSize", mappingCornerLeafSize, 0.2);
  184. nh.param<float>("lio_sam/mappingSurfLeafSize", mappingSurfLeafSize, 0.2);
  185. nh.param<float>("lio_sam/z_tollerance", z_tollerance, FLT_MAX);
  186. nh.param<float>("lio_sam/rotation_tollerance", rotation_tollerance, FLT_MAX);
  187. nh.param<int>("lio_sam/numberOfCores", numberOfCores, 2);
  188. nh.param<double>("lio_sam/mappingProcessInterval", mappingProcessInterval, 0.15);
  189. nh.param<float>("lio_sam/surroundingkeyframeAddingDistThreshold", surroundingkeyframeAddingDistThreshold, 1.0);
  190. nh.param<float>("lio_sam/surroundingkeyframeAddingAngleThreshold", surroundingkeyframeAddingAngleThreshold, 0.2);
  191. nh.param<float>("lio_sam/surroundingKeyframeDensity", surroundingKeyframeDensity, 1.0);
  192. nh.param<float>("lio_sam/surroundingKeyframeSearchRadius", surroundingKeyframeSearchRadius, 50.0);
  193. nh.param<bool>("lio_sam/loopClosureEnableFlag", loopClosureEnableFlag, false);
  194. nh.param<float>("lio_sam/loopClosureFrequency", loopClosureFrequency, 1.0);
  195. nh.param<int>("lio_sam/surroundingKeyframeSize", surroundingKeyframeSize, 50);
  196. nh.param<float>("lio_sam/historyKeyframeSearchRadius", historyKeyframeSearchRadius, 10.0);
  197. nh.param<float>("lio_sam/historyKeyframeSearchTimeDiff", historyKeyframeSearchTimeDiff, 30.0);
  198. nh.param<int>("lio_sam/historyKeyframeSearchNum", historyKeyframeSearchNum, 25);
  199. nh.param<float>("lio_sam/historyKeyframeFitnessScore", historyKeyframeFitnessScore, 0.3);
  200. nh.param<float>("lio_sam/globalMapVisualizationSearchRadius", globalMapVisualizationSearchRadius, 1e3);
  201. nh.param<float>("lio_sam/globalMapVisualizationPoseDensity", globalMapVisualizationPoseDensity, 10.0);
  202. nh.param<float>("lio_sam/globalMapVisualizationLeafSize", globalMapVisualizationLeafSize, 1.0);
  203. nh.param<int>("lio_sam/addKeyFameNum", addKeyFameNum, 0);
  204. nh.param<float>("lio_sam/ndtMinScore", ndtMinScore, 0.05);
  205. usleep(100);
  206. }
  207. sensor_msgs::Imu imuConverter(const sensor_msgs::Imu& imu_in)
  208. {
  209. sensor_msgs::Imu imu_out = imu_in;
  210. // rotate acceleration
  211. Eigen::Vector3d acc(imu_in.linear_acceleration.x, imu_in.linear_acceleration.y, imu_in.linear_acceleration.z);
  212. acc = extRot * acc;
  213. imu_out.linear_acceleration.x = acc.x();
  214. imu_out.linear_acceleration.y = acc.y();
  215. imu_out.linear_acceleration.z = acc.z();
  216. // rotate gyroscope
  217. Eigen::Vector3d gyr(imu_in.angular_velocity.x, imu_in.angular_velocity.y, imu_in.angular_velocity.z);
  218. gyr = extRot * gyr;
  219. imu_out.angular_velocity.x = gyr.x();
  220. imu_out.angular_velocity.y = gyr.y();
  221. imu_out.angular_velocity.z = gyr.z();
  222. // rotate roll pitch yaw
  223. Eigen::Quaterniond q_from(imu_in.orientation.w, imu_in.orientation.x, imu_in.orientation.y, imu_in.orientation.z);
  224. Eigen::Quaterniond q_final = q_from * extQRPY;
  225. imu_out.orientation.x = q_final.x();
  226. imu_out.orientation.y = q_final.y();
  227. imu_out.orientation.z = q_final.z();
  228. imu_out.orientation.w = q_final.w();
  229. if (sqrt(q_final.x()*q_final.x() + q_final.y()*q_final.y() + q_final.z()*q_final.z() + q_final.w()*q_final.w()) < 0.1)
  230. {
  231. ROS_ERROR("Invalid quaternion, please use a 9-axis IMU!");
  232. ros::shutdown();
  233. }
  234. return imu_out;
  235. }
  236. };
  237. sensor_msgs::PointCloud2 publishCloud(ros::Publisher *thisPub, pcl::PointCloud<PointType>::Ptr thisCloud, ros::Time thisStamp, std::string thisFrame)
  238. {
  239. sensor_msgs::PointCloud2 tempCloud;
  240. pcl::toROSMsg(*thisCloud, tempCloud);
  241. tempCloud.header.stamp = thisStamp;
  242. tempCloud.header.frame_id = thisFrame;
  243. if (thisPub->getNumSubscribers() != 0)
  244. thisPub->publish(tempCloud);
  245. return tempCloud;
  246. }
  247. template<typename T>
  248. double ROS_TIME(T msg)
  249. {
  250. return msg->header.stamp.toSec();
  251. }
  252. template<typename T>
  253. void imuAngular2rosAngular(sensor_msgs::Imu *thisImuMsg, T *angular_x, T *angular_y, T *angular_z)
  254. {
  255. *angular_x = thisImuMsg->angular_velocity.x;
  256. *angular_y = thisImuMsg->angular_velocity.y;
  257. *angular_z = thisImuMsg->angular_velocity.z;
  258. }
  259. template<typename T>
  260. void imuAccel2rosAccel(sensor_msgs::Imu *thisImuMsg, T *acc_x, T *acc_y, T *acc_z)
  261. {
  262. *acc_x = thisImuMsg->linear_acceleration.x;
  263. *acc_y = thisImuMsg->linear_acceleration.y;
  264. *acc_z = thisImuMsg->linear_acceleration.z;
  265. }
  266. template<typename T>
  267. void imuRPY2rosRPY(sensor_msgs::Imu *thisImuMsg, T *rosRoll, T *rosPitch, T *rosYaw)
  268. {
  269. double imuRoll, imuPitch, imuYaw;
  270. tf::Quaternion orientation;
  271. tf::quaternionMsgToTF(thisImuMsg->orientation, orientation);
  272. tf::Matrix3x3(orientation).getRPY(imuRoll, imuPitch, imuYaw);
  273. *rosRoll = imuRoll;
  274. *rosPitch = imuPitch;
  275. *rosYaw = imuYaw;
  276. }
  277. float pointDistance(PointType p)
  278. {
  279. return sqrt(p.x*p.x + p.y*p.y + p.z*p.z);
  280. }
  281. float pointDistance(PointType p1, PointType p2)
  282. {
  283. return sqrt((p1.x-p2.x)*(p1.x-p2.x) + (p1.y-p2.y)*(p1.y-p2.y) + (p1.z-p2.z)*(p1.z-p2.z));
  284. }
  285. #endif