123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245 |
- /************************************************************
- *
- * Copyright (c) 2021, University of California, Los Angeles
- *
- * Authors: Kenny J. Chen, Brett T. Lopez
- * Contact: kennyjchen@ucla.edu, btlopez@ucla.edu
- *
- ***********************************************************/
- #include "dlo/dlo.h"
- class dlo::OdomNode {
- public:
- OdomNode(ros::NodeHandle node_handle);
- ~OdomNode();
- static void abort() {
- abort_ = true;
- }
- void start();
- void stop();
- private:
- void abortTimerCB(const ros::TimerEvent& e);
- void icpCB(const sensor_msgs::PointCloud2ConstPtr& pc);
- void imuCB(const sensor_msgs::Imu::ConstPtr& imu);
- sensor_msgs::Imu imuConverter(const sensor_msgs::Imu& imu_in);
- void getParams();
- void publishToROS();
- void publishPose();
- void publishTransform();
- void publishKeyframe();
- void preprocessPoints();
- void initializeInputTarget();
- void setInputSources();
- void initializeDLO();
- void gravityAlign();
- void getNextPose();
- void integrateIMU();
- void propagateS2S(Eigen::Matrix4f T);
- void propagateS2M();
- void setAdaptiveParams();
- void computeMetrics();
- void computeSpaciousness();
- void transformCurrentScan();
- void updateKeyframes();
- void computeConvexHull();
- void computeConcaveHull();
- void pushSubmapIndices(std::vector<float> dists, int k);
- void getSubmapKeyframes();
- void debug();
- double first_imu_time;
- ros::NodeHandle nh;
- ros::Timer abort_timer;
- ros::Subscriber icp_sub;
- ros::Subscriber imu_sub;
- ros::Publisher odom_pub;
- ros::Publisher keyframe_pub;
- ros::Publisher kf_pub;
- std::vector<std::pair<Eigen::Vector3f, Eigen::Quaternionf>> trajectory;
- std::vector<std::pair<std::pair<Eigen::Vector3f, Eigen::Quaternionf>, pcl::PointCloud<PointType>::Ptr>> keyframes;
- std::vector<std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>>> keyframe_normals;
- std::atomic<bool> dlo_initialized;
- std::atomic<bool> imu_calibrated;
- std::atomic<bool> normals_initialized;
- std::string odom_frame;
- std::string child_frame;
- Eigen::Matrix3d extRot;
- Eigen::Matrix3d extRPY;
- Eigen::Vector3d extTrans;
- Eigen::Quaterniond extQRPY;
- pcl::PointCloud<PointType>::Ptr original_scan;
- pcl::PointCloud<PointType>::Ptr current_scan;
- pcl::PointCloud<PointType>::Ptr current_scan_t;
- pcl::PointCloud<PointType>::Ptr keyframes_cloud;
- pcl::PointCloud<PointType>::Ptr keyframe_cloud;
- int num_keyframes;
- pcl::ConvexHull<PointType> convex_hull;
- pcl::ConcaveHull<PointType> concave_hull;
- std::vector<int> keyframe_convex;
- std::vector<int> keyframe_concave;
- pcl::PointCloud<PointType>::Ptr submap_cloud;
- std::vector<Eigen::Matrix4d, Eigen::aligned_allocator<Eigen::Matrix4d>> submap_normals;
- std::vector<int> submap_kf_idx_curr;
- std::vector<int> submap_kf_idx_prev;
- std::atomic<bool> submap_hasChanged;
- pcl::PointCloud<PointType>::Ptr source_cloud;
- pcl::PointCloud<PointType>::Ptr target_cloud;
- ros::Time scan_stamp;
- double curr_frame_stamp;
- double prev_frame_stamp;
- std::vector<double> comp_times;
- nano_gicp::NanoGICP<PointType, PointType> gicp_s2s;
- nano_gicp::NanoGICP<PointType, PointType> gicp;
- pcl::CropBox<PointType> crop;
- pcl::VoxelGrid<PointType> vf_scan;
- pcl::VoxelGrid<PointType> vf_submap;
- nav_msgs::Odometry odom;
- nav_msgs::Odometry kf;
- geometry_msgs::PoseStamped pose_ros;
- Eigen::Matrix4f T;
- Eigen::Matrix4f T_s2s, T_s2s_prev;
- Eigen::Quaternionf q_final;
- Eigen::Vector3f pose_s2s;
- Eigen::Matrix3f rotSO3_s2s;
- Eigen::Quaternionf rotq_s2s;
- Eigen::Vector3f pose;
- Eigen::Matrix3f rotSO3;
- Eigen::Quaternionf rotq;
- Eigen::Matrix4f imu_SE3;
- struct XYZd {
- double x;
- double y;
- double z;
- };
- struct ImuBias {
- XYZd gyro;
- XYZd accel;
- };
- ImuBias imu_bias;
- struct ImuMeas {
- double stamp;
- XYZd ang_vel;
- XYZd lin_accel;
- };
- ImuMeas imu_meas;
- boost::circular_buffer<ImuMeas> imu_buffer;
- static bool comparatorImu(ImuMeas m1, ImuMeas m2) {
- return (m1.stamp < m2.stamp);
- };
- struct Metrics {
- std::vector<float> spaciousness;
- };
- Metrics metrics;
- static std::atomic<bool> abort_;
- std::atomic<bool> stop_publish_thread;
- std::atomic<bool> stop_publish_keyframe_thread;
- std::atomic<bool> stop_metrics_thread;
- std::atomic<bool> stop_debug_thread;
- std::thread publish_thread;
- std::thread publish_keyframe_thread;
- std::thread metrics_thread;
- std::thread debug_thread;
- std::mutex mtx_imu;
- std::string cpu_type;
- std::vector<double> cpu_percents;
- clock_t lastCPU, lastSysCPU, lastUserCPU;
- int numProcessors;
- // Parameters
- std::string version_;
- bool gravity_align_;
- double keyframe_thresh_dist_;
- double keyframe_thresh_rot_;
- int submap_knn_;
- int submap_kcv_;
- int submap_kcc_;
- double submap_concave_alpha_;
- bool crop_use_;
- double crop_size_;
- bool vf_scan_use_;
- double vf_scan_res_;
- bool vf_submap_use_;
- double vf_submap_res_;
- bool adaptive_params_use_;
- bool imu_use_;
- int imu_calib_time_;
- int imu_buffer_size_;
- int gicp_min_num_points_;
- int gicps2s_k_correspondences_;
- double gicps2s_max_corr_dist_;
- int gicps2s_max_iter_;
- double gicps2s_transformation_ep_;
- double gicps2s_euclidean_fitness_ep_;
- int gicps2s_ransac_iter_;
- double gicps2s_ransac_inlier_thresh_;
- int gicps2m_k_correspondences_;
- double gicps2m_max_corr_dist_;
- int gicps2m_max_iter_;
- double gicps2m_transformation_ep_;
- double gicps2m_euclidean_fitness_ep_;
- int gicps2m_ransac_iter_;
- double gicps2m_ransac_inlier_thresh_;
- };
|