diff --git a/CMakeLists.txt b/CMakeLists.txt index 005b8cd..173b94f 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,17 +3,17 @@ project(point_lio) SET(CMAKE_BUILD_TYPE "Debug") -ADD_COMPILE_OPTIONS(-std=c++14 ) -ADD_COMPILE_OPTIONS(-std=c++14 ) -set( CMAKE_CXX_FLAGS "-std=c++14 -O3" ) +ADD_COMPILE_OPTIONS(-std=c++17 ) +ADD_COMPILE_OPTIONS(-std=c++17 ) +set( CMAKE_CXX_FLAGS "-std=c++17 -O3" ) add_definitions(-DROOT_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/\") set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fexceptions" ) -set(CMAKE_CXX_STANDARD 14) +set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) -set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -pthread -std=c++0x -std=c++14 -fexceptions") +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -pthread -std=c++0x -std=c++17 -fexceptions") #add_compile_definitions(BOOST_BIND_GLOBAL_PLACEHOLDERS) diff --git a/include/IKFoM/IKFoM_toolkit/esekfom/esekfom.hpp b/include/IKFoM/IKFoM_toolkit/esekfom/esekfom.hpp index 75e2f02..2ec4363 100755 --- a/include/IKFoM/IKFoM_toolkit/esekfom/esekfom.hpp +++ b/include/IKFoM/IKFoM_toolkit/esekfom/esekfom.hpp @@ -38,8 +38,7 @@ #include #include - -#include +#include #include #include #include @@ -57,6 +56,7 @@ namespace esekfom { using namespace Eigen; +using namespace boost::placeholders; template struct dyn_share_modified diff --git a/src/IMU_Processing.cpp b/src/IMU_Processing.cpp index dcfef1a..7131b73 100755 --- a/src/IMU_Processing.cpp +++ b/src/IMU_Processing.cpp @@ -1,4 +1,5 @@ #include "IMU_Processing.h" +#include "parameters.h" const bool time_list(PointType &x, PointType &y) {return (x.curvature < y.curvature);}; @@ -116,7 +117,7 @@ void ImuProcess::Process(const MeasureGroup &meas, PointCloudXYZI::Ptr cur_pcl_u if (init_iter_num > MAX_INI_COUNT) { - ROS_INFO("IMU Initializing: %.1f %%", 100.0); + RCLCPP_WARN(logger, "IMU Initializing: %.1f %%", 100.0); imu_need_init_ = false; *cur_pcl_un_ = *(meas.lidar); } diff --git a/src/IMU_Processing.h b/src/IMU_Processing.h index 280c774..5e62737 100755 --- a/src/IMU_Processing.h +++ b/src/IMU_Processing.h @@ -10,6 +10,8 @@ #include // #include "Estimator.h" #include +#include +#include #include #include #include diff --git a/src/laserMapping.cpp b/src/laserMapping.cpp index fc02e26..dda3596 100755 --- a/src/laserMapping.cpp +++ b/src/laserMapping.cpp @@ -46,6 +46,8 @@ nav_msgs::msg::Path path; nav_msgs::msg::Odometry odomAftMapped; geometry_msgs::msg::PoseStamped msg_body_pose; +rclcpp::Logger logger = rclcpp::get_logger("laserMapping"); + void SigHandle(int sig) { flg_exit = true; @@ -268,7 +270,7 @@ void set_posestamp(T & out) } } -void publish_odometry(const rclcpp::Publisher::SharedPtr & pubOdomAftMapped) +void publish_odometry(const rclcpp::Publisher::SharedPtr & pubOdomAftMapped, const std::shared_ptr &tf_br) { odomAftMapped.header.frame_id = "camera_init"; odomAftMapped.child_frame_id = "body"; @@ -384,12 +386,11 @@ int main(int argc, char** argv) rclcpp::Publisher::SharedPtr pubLaserCloudMap = nh->create_publisher("/Laser_map", 1000); rclcpp::Publisher::SharedPtr pubOdomAftMapped = nh->create_publisher("/aft_mapped_to_init", 1000); rclcpp::Publisher::SharedPtr pubPath = nh->create_publisher("/path", 1000); - ("/path", 1000); rclcpp::Publisher::SharedPtr plane_pub = nh->create_publisher("/planner_normal", 1000); - tf2_ros::TransformBroadcaster::SharedPtr tf_broadcaster = std::make_shared(nh); + std::shared_ptr tf_broadcaster = std::make_shared(nh); //------------------------------------------------------------------------------------------------------ signal(SIGINT, SigHandle); - rclcpp::Rate loop_rate(500); + rclcpp::Rate rate(500); while (rclcpp::ok()) { @@ -1055,8 +1056,7 @@ int main(int argc, char** argv) dump_lio_state_to_log(fp); } } - status = ros::ok(); - loop_rate.sleep(); + rate.sleep(); } //--------------------------save map----------------------------------- /* 1. make sure you have enough memories diff --git a/src/li_initialization.cpp b/src/li_initialization.cpp index 187dc2c..2f9ba8a 100755 --- a/src/li_initialization.cpp +++ b/src/li_initialization.cpp @@ -189,9 +189,10 @@ void imu_cbk(const sensor_msgs::msg::Imu::ConstSharedPtr &msg_in) // publish_count ++; sensor_msgs::msg::Imu::SharedPtr msg(new sensor_msgs::msg::Imu(*msg_in)); + double timestamp = get_time_sec(msg->header.stamp); + msg->header.stamp = get_ros_time(timestamp - timediff_imu_wrt_lidar - time_lag_IMU_wtr_lidar); - double timestamp = get_time_sec(msg->header.stamp); // printf("time_diff%f, %f, %f\n", last_timestamp_imu - timestamp, last_timestamp_imu, timestamp); if (timestamp < last_timestamp_imu) @@ -309,7 +310,7 @@ bool sync_packages(MeasureGroup &meas) /*** push imu data, and pop from imu buffer ***/ if (p_imu->imu_need_init_) { - double imu_time = imu_deque.front()->header.stamp.toSec(); + double imu_time = get_time_sec(imu_deque.front()->header.stamp); imu_next = *(imu_deque.front()); meas.imu.shrink_to_fit(); while (imu_time < lidar_end_time) @@ -318,7 +319,7 @@ bool sync_packages(MeasureGroup &meas) imu_last = imu_next; imu_deque.pop_front(); if(imu_deque.empty()) break; - imu_time = imu_deque.front()->header.stamp.toSec(); // can be changed + imu_time = get_time_sec(imu_deque.front()->header.stamp); imu_next = *(imu_deque.front()); } } @@ -330,7 +331,7 @@ bool sync_packages(MeasureGroup &meas) /*** push imu data, and pop from imu buffer ***/ if (p_imu->imu_need_init_) { - double imu_time = imu_deque.front()->header.stamp.toSec(); + double imu_time = get_time_sec(imu_deque.front()->header.stamp); meas.imu.shrink_to_fit(); imu_next = *(imu_deque.front()); @@ -340,7 +341,7 @@ bool sync_packages(MeasureGroup &meas) imu_last = imu_next; imu_deque.pop_front(); if(imu_deque.empty()) break; - imu_time = imu_deque.front()->header.stamp.toSec(); // can be changed + imu_time = get_time_sec(imu_deque.front()->header.stamp); imu_next = *(imu_deque.front()); } } diff --git a/src/parameters.h b/src/parameters.h index 2f400a1..604e6a9 100755 --- a/src/parameters.h +++ b/src/parameters.h @@ -75,6 +75,8 @@ extern double time_update_last, time_current, time_predict_last_const, t_last; extern MeasureGroup Measures; +extern rclcpp::Logger logger; + extern ofstream fout_out, fout_imu_pbp; void readParameters(rclcpp::Node::SharedPtr &nh); void open_file(); diff --git a/src/preprocess.cpp b/src/preprocess.cpp index a8c9715..5f59539 100755 --- a/src/preprocess.cpp +++ b/src/preprocess.cpp @@ -1,3 +1,4 @@ +#include "common_lib.h" #include "preprocess.h" #define RETURN0 0x00 @@ -44,13 +45,13 @@ void Preprocess::set(bool feat_en, int lid_type, double bld, int pfilt_num) point_filter_num = pfilt_num; } -void Preprocess::process(const livox_ros_driver::CustomMsg::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out) +void Preprocess::process(const livox_ros_driver2::msg::CustomMsg::ConstSharedPtr &msg, PointCloudXYZI::Ptr &pcl_out) { avia_handler(msg); *pcl_out = pl_surf; } -void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointCloudXYZI::Ptr &pcl_out) +void Preprocess::process(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, PointCloudXYZI::Ptr &pcl_out) { switch (time_unit) { @@ -93,7 +94,7 @@ void Preprocess::process(const sensor_msgs::PointCloud2::ConstPtr &msg, PointClo } void Preprocess::process_cut_frame_livox(const livox_ros_driver2::msg::CustomMsg::ConstSharedPtr &msg, - deque &pcl_out, deque &time_lidar, + std::deque &pcl_out, std::deque &time_lidar, const int required_frame_num, int scan_count) { int plsize = msg->point_num; pl_surf.clear(); @@ -141,7 +142,7 @@ void Preprocess::process_cut_frame_livox(const livox_ros_driver2::msg::CustomMsg for (uint i = 1; i < valid_pcl_size; i++) { valid_num++; //Compute new opffset time of each point:ms - pl_surf[i].curvature += msg->header.stamp.toSec() * 1000 - last_frame_end_time; + pl_surf[i].curvature += get_time_sec(msg->header.stamp) * 1000 - last_frame_end_time; pcl_cut.push_back(pl_surf[i]); if (valid_num == (int((cut_num + 1) * valid_pcl_size / required_cut_num) - 1)) { cut_num++; @@ -158,8 +159,8 @@ void Preprocess::process_cut_frame_livox(const livox_ros_driver2::msg::CustomMsg } #define MAX_LINE_NUM 128 void -Preprocess::process_cut_frame_pcl2(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, deque &pcl_out, - deque &time_lidar, const int required_frame_num, int scan_count) { +Preprocess::process_cut_frame_pcl2(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, std::deque &pcl_out, + std::deque &time_lidar, const int required_frame_num, int scan_count) { pl_surf.clear(); pl_corn.clear(); pl_full.clear(); @@ -371,7 +372,7 @@ void Preprocess::oust64_handler(const sensor_msgs::msg::PointCloud2::ConstShared pl_surf.reserve(plsize); - double time_stamp = msg->header.stamp.toSec(); + double time_stamp = get_time_sec(msg->header.stamp); // cout << "===================================" << endl; // printf("Pt size = %d, N_SCANS = %d\r\n", plsize, N_SCANS); for (int i = 0; i < pl_orig.points.size(); i++) @@ -872,10 +873,10 @@ void Preprocess::give_feature(pcl::PointCloud &pl, vector &t } } -void Preprocess::pub_func(PointCloudXYZI &pl, const ros::Time &ct) +void Preprocess::pub_func(PointCloudXYZI &pl, const rclcpp::Time &ct) { pl.height = 1; pl.width = pl.size(); - sensor_msgs::PointCloud2 output; + sensor_msgs::msg::PointCloud2 output; pcl::toROSMsg(pl, output); output.header.frame_id = "livox"; output.header.stamp = ct; diff --git a/src/preprocess.h b/src/preprocess.h index f6fdce3..76feaee 100755 --- a/src/preprocess.h +++ b/src/preprocess.h @@ -1,8 +1,15 @@ +#pragma once + +#include #include #include #include #include +#include +#include +#include + using namespace std; #define IS_VALID(a) ((abs(a)>1e8) ? true : false) @@ -107,9 +114,9 @@ class Preprocess Preprocess(); ~Preprocess(); - void process_cut_frame_livox(const livox_ros_driver2::msg::CustomMsg::ConstSharedPtr &msg, deque &pcl_out, deque &time_lidar, const int required_frame_num, int scan_count); + void process_cut_frame_livox(const livox_ros_driver2::msg::CustomMsg::ConstSharedPtr &msg, std::deque &pcl_out, std::deque &time_lidar, const int required_frame_num, int scan_count); - void process_cut_frame_pcl2(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, deque &pcl_out, deque &time_lidar, const int required_frame_num, int scan_count); + void process_cut_frame_pcl2(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, std::deque &pcl_out, std::deque &time_lidar, const int required_frame_num, int scan_count); void process(const livox_ros_driver2::msg::CustomMsg::ConstSharedPtr &msg, PointCloudXYZI::Ptr &pcl_out); void process(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg, PointCloudXYZI::Ptr &pcl_out); @@ -123,7 +130,7 @@ class Preprocess int lidar_type, point_filter_num, N_SCANS, SCAN_RATE, time_unit; double blind, det_range; bool given_offset_time; - ros::Publisher pub_full, pub_surf, pub_corn; + // ros::Publisher pub_full, pub_surf, pub_corn; private: @@ -132,7 +139,7 @@ class Preprocess void velodyne_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); void hesai_handler(const sensor_msgs::msg::PointCloud2::ConstSharedPtr &msg); void give_feature(PointCloudXYZI &pl, vector &types); - void pub_func(PointCloudXYZI &pl, const ros::Time &ct); + void pub_func(PointCloudXYZI &pl, const rclcpp::Time &ct); int plane_judge(const PointCloudXYZI &pl, vector &types, uint i, uint &i_nex, Eigen::Vector3d &curr_direct); bool small_plane(const PointCloudXYZI &pl, vector &types, uint i_cur, uint &i_nex, Eigen::Vector3d &curr_direct); bool edge_jump_judge(const PointCloudXYZI &pl, vector &types, uint i, Surround nor_dir);