odom.h 5.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245
  1. /************************************************************
  2. *
  3. * Copyright (c) 2021, University of California, Los Angeles
  4. *
  5. * Authors: Kenny J. Chen, Brett T. Lopez
  6. * Contact: kennyjchen@ucla.edu, btlopez@ucla.edu
  7. *
  8. ***********************************************************/
  9. #include "dlo/dlo.h"
  10. class dlo::OdomNode {
  11. public:
  12. OdomNode(ros::NodeHandle node_handle);
  13. ~OdomNode();
  14. static void abort() {
  15. abort_ = true;
  16. }
  17. void start();
  18. void stop();
  19. private:
  20. void abortTimerCB(const ros::TimerEvent& e);
  21. void icpCB(const sensor_msgs::PointCloud2ConstPtr& pc);
  22. void imuCB(const sensor_msgs::Imu::ConstPtr& imu);
  23. sensor_msgs::Imu imuConverter(const sensor_msgs::Imu& imu_in);
  24. void getParams();
  25. void publishToROS();
  26. void publishPose();
  27. void publishTransform();
  28. void publishKeyframe();
  29. void preprocessPoints();
  30. void initializeInputTarget();
  31. void setInputSources();
  32. void initializeDLO();
  33. void gravityAlign();
  34. void getNextPose();
  35. void integrateIMU();
  36. void propagateS2S(Eigen::Matrix4f T);
  37. void propagateS2M();
  38. void setAdaptiveParams();
  39. void computeMetrics();
  40. void computeSpaciousness();
  41. void transformCurrentScan();
  42. void updateKeyframes();
  43. void computeConvexHull();
  44. void computeConcaveHull();
  45. void pushSubmapIndices(std::vector<float> dists, int k);
  46. void getSubmapKeyframes();
  47. void debug();
  48. double first_imu_time;
  49. ros::NodeHandle nh;
  50. ros::Timer abort_timer;
  51. ros::Subscriber icp_sub;
  52. ros::Subscriber imu_sub;
  53. ros::Publisher odom_pub;
  54. ros::Publisher keyframe_pub;
  55. ros::Publisher kf_pub;
  56. std::vector<std::pair<Eigen::Vector3f, Eigen::Quaternionf>> trajectory;
  57. std::vector<std::pair<std::pair<Eigen::Vector3f, Eigen::Quaternionf>, pcl::PointCloud<PointType>::Ptr>> keyframes;
  58. std::vector<std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>> keyframe_normals;
  59. std::atomic<bool> dlo_initialized;
  60. std::atomic<bool> imu_calibrated;
  61. std::atomic<bool> normals_initialized;
  62. std::string odom_frame;
  63. std::string child_frame;
  64. Eigen::Matrix3d extRot;
  65. Eigen::Matrix3d extRPY;
  66. Eigen::Vector3d extTrans;
  67. Eigen::Quaterniond extQRPY;
  68. pcl::PointCloud<PointType>::Ptr original_scan;
  69. pcl::PointCloud<PointType>::Ptr current_scan;
  70. pcl::PointCloud<PointType>::Ptr current_scan_t;
  71. pcl::PointCloud<PointType>::Ptr keyframes_cloud;
  72. pcl::PointCloud<PointType>::Ptr keyframe_cloud;
  73. int num_keyframes;
  74. pcl::ConvexHull<PointType> convex_hull;
  75. pcl::ConcaveHull<PointType> concave_hull;
  76. std::vector<int> keyframe_convex;
  77. std::vector<int> keyframe_concave;
  78. pcl::PointCloud<PointType>::Ptr submap_cloud;
  79. std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> submap_normals;
  80. std::vector<int> submap_kf_idx_curr;
  81. std::vector<int> submap_kf_idx_prev;
  82. std::atomic<bool> submap_hasChanged;
  83. pcl::PointCloud<PointType>::Ptr source_cloud;
  84. pcl::PointCloud<PointType>::Ptr target_cloud;
  85. ros::Time scan_stamp;
  86. double curr_frame_stamp;
  87. double prev_frame_stamp;
  88. std::vector<double> comp_times;
  89. nano_gicp::NanoGICP<PointType, PointType> gicp_s2s;
  90. nano_gicp::NanoGICP<PointType, PointType> gicp;
  91. pcl::CropBox<PointType> crop;
  92. pcl::VoxelGrid<PointType> vf_scan;
  93. pcl::VoxelGrid<PointType> vf_submap;
  94. nav_msgs::Odometry odom;
  95. nav_msgs::Odometry kf;
  96. geometry_msgs::PoseStamped pose_ros;
  97. Eigen::Matrix4f T;
  98. Eigen::Matrix4f T_s2s, T_s2s_prev;
  99. Eigen::Quaternionf q_final;
  100. Eigen::Vector3f pose_s2s;
  101. Eigen::Matrix3f rotSO3_s2s;
  102. Eigen::Quaternionf rotq_s2s;
  103. Eigen::Vector3f pose;
  104. Eigen::Matrix3f rotSO3;
  105. Eigen::Quaternionf rotq;
  106. Eigen::Matrix4f imu_SE3;
  107. struct XYZd {
  108. double x;
  109. double y;
  110. double z;
  111. };
  112. struct ImuBias {
  113. XYZd gyro;
  114. XYZd accel;
  115. };
  116. ImuBias imu_bias;
  117. struct ImuMeas {
  118. double stamp;
  119. XYZd ang_vel;
  120. XYZd lin_accel;
  121. };
  122. ImuMeas imu_meas;
  123. boost::circular_buffer<ImuMeas> imu_buffer;
  124. static bool comparatorImu(ImuMeas m1, ImuMeas m2) {
  125. return (m1.stamp < m2.stamp);
  126. };
  127. struct Metrics {
  128. std::vector<float> spaciousness;
  129. };
  130. Metrics metrics;
  131. static std::atomic<bool> abort_;
  132. std::atomic<bool> stop_publish_thread;
  133. std::atomic<bool> stop_publish_keyframe_thread;
  134. std::atomic<bool> stop_metrics_thread;
  135. std::atomic<bool> stop_debug_thread;
  136. std::thread publish_thread;
  137. std::thread publish_keyframe_thread;
  138. std::thread metrics_thread;
  139. std::thread debug_thread;
  140. std::mutex mtx_imu;
  141. std::string cpu_type;
  142. std::vector<double> cpu_percents;
  143. clock_t lastCPU, lastSysCPU, lastUserCPU;
  144. int numProcessors;
  145. // Parameters
  146. std::string version_;
  147. bool gravity_align_;
  148. double keyframe_thresh_dist_;
  149. double keyframe_thresh_rot_;
  150. int submap_knn_;
  151. int submap_kcv_;
  152. int submap_kcc_;
  153. double submap_concave_alpha_;
  154. bool crop_use_;
  155. double crop_size_;
  156. bool vf_scan_use_;
  157. double vf_scan_res_;
  158. bool vf_submap_use_;
  159. double vf_submap_res_;
  160. bool adaptive_params_use_;
  161. bool imu_use_;
  162. int imu_calib_time_;
  163. int imu_buffer_size_;
  164. int gicp_min_num_points_;
  165. int gicps2s_k_correspondences_;
  166. double gicps2s_max_corr_dist_;
  167. int gicps2s_max_iter_;
  168. double gicps2s_transformation_ep_;
  169. double gicps2s_euclidean_fitness_ep_;
  170. int gicps2s_ransac_iter_;
  171. double gicps2s_ransac_inlier_thresh_;
  172. int gicps2m_k_correspondences_;
  173. double gicps2m_max_corr_dist_;
  174. int gicps2m_max_iter_;
  175. double gicps2m_transformation_ep_;
  176. double gicps2m_euclidean_fitness_ep_;
  177. int gicps2m_ransac_iter_;
  178. double gicps2m_ransac_inlier_thresh_;
  179. };