激光slam傳感器處理:2D激光雷達運動畸變去除原理解釋、代碼實現

2D激光雷達運動畸變去除原理解釋、代碼實現

在這裏插入圖片描述
在這裏插入圖片描述
在這裏插入圖片描述
在這裏插入圖片描述
在這裏插入圖片描述

主要代碼如下:

如果需要激光雷達去畸變完整功能包,在下面公衆號發送激光雷達,即可獲取。
在這裏插入圖片描述

#include <ros/ros.h>
#include <tf/tf.h>
#include <tf/transform_broadcaster.h>
#include <tf/transform_listener.h>
#include <sensor_msgs/LaserScan.h>
#include <iostream>
#include <dirent.h>
#include <fstream>
#include <iostream>
#include <string>
//如果使用調試模式,可視化點雲,需要安裝PCL
#define debug_ 0

#if debug_
#include <pcl-1.7/pcl/point_cloud.h>
#include <pcl/point_types.h>
#include <pcl-1.7/pcl/visualization/cloud_viewer.h>
pcl::visualization::CloudViewer g_PointCloudView("PointCloud View");//初始化一個pcl窗口
#endif

class LidarMotionCalibrator
{
public:
    //構造函數,初始化tf_、訂閱者、回調函數ScanCallBack
    LidarMotionCalibrator(tf::TransformListener* tf)
    {
        tf_ = tf;
        scan_sub_ = nh_.subscribe(scan_sub_name_, 10, &LidarMotionCalibrator::ScanCallBack, this);
        scan_pub_ = nh_.advertise<sensor_msgs::LaserScan>(scan_pub_name_, 1000);
    }
    //析構函數,釋放tf_
    ~LidarMotionCalibrator()
    {
        if(tf_!=NULL)
            delete tf_;
    }
    // 拿到原始的激光數據來進行處理
    void ScanCallBack(const sensor_msgs::LaserScanConstPtr& scan_msg)
    {
        //轉換到矯正需要的數據
        ros::Time startTime, endTime;
        //一幀scan數據到來首先得出,開始結束的時間戳、數據的size
        startTime = scan_msg->header.stamp;
        sensor_msgs::LaserScan laserScanMsg = *scan_msg;

        //得到最終點的時間
        int beamNum = laserScanMsg.ranges.size();
        endTime = startTime + ros::Duration(laserScanMsg.time_increment * beamNum);

        // 將數據複製出來
        std::vector<double> angles,ranges;
        for(int i = 0; i < beamNum;i++)
        {
            double lidar_dist = laserScanMsg.ranges[i];//單位米
            double lidar_angle = laserScanMsg.angle_min + laserScanMsg.angle_increment * i;//單位弧度

            ranges.push_back(lidar_dist);
            angles.push_back(lidar_angle);
        }
        #if debug_
        visual_cloud_.clear();
        //轉換爲pcl::pointcloud for visuailization
        //數據矯正前、封裝打算點雲可視化、紅色
        visual_cloud_scan(ranges,angles,255,0,0);
        #endif
        //進行矯正
        Lidar_Calibration(ranges,angles,
                          startTime,
                          endTime,
                          tf_);
        //數據矯正後、封裝打算點雲可視化、綠色
        //轉換爲pcl::pointcloud for visuailization
        #if debug_
        visual_cloud_scan(ranges,angles,0,255,0);
        #endif
        //發佈矯正後的scan
        //ROS_INFO("scan_time:%f",ros::Duration(laserScanMsg.time_increment * beamNum).toSec());
        scan_cal_pub(ranges,startTime,ros::Duration(laserScanMsg.time_increment * beamNum).toSec());
        //進行顯示
        #if debug_
        g_PointCloudView.showCloud(visual_cloud_.makeShared());
        #endif
    }
	/*==============================================================
	聲明:這裏的scan數據重新封裝並不完全正確,每個去畸變的激光數據的角度
	並沒有封裝到新的scan中,原因是sensor_msgs::LaserScan的角度是按照分
	辨率給定的,相鄰相差一致,而去畸變的角度差是不固定,如果重新定義scan
	的數據類型,其他功能包需要改動的就太多了,暫時,不做更改。雖然不完全
	正確,但是除了機器人猛烈旋轉情況下的數據,沒有去畸變成功,其他直線或
	者低速旋轉運動的畸變還是有效的去除了。之後,有機會的話,我會把這部分
	完全修改正確,屆時,將更新本篇代碼部分。這裏不影響使用。
	==============================================================*/
    //矯正之後的scan數據的發佈函數,這裏默認發佈所有360度的所有數據,正着安裝,所填寫的參數是rplidar A1
    void scan_cal_pub(const std::vector<double> &ranges,ros::Time pubTime,double scan_time)
    {
        //定義sensor_msgs::LaserScan數據
        sensor_msgs::LaserScan tempScan;
        tempScan.header.stamp=pubTime;
        tempScan.header.frame_id=scan_frame_name_;
        tempScan.angle_min=-3.12413907051;
        tempScan.angle_max=3.14159274101;
        tempScan.angle_increment=(tempScan.angle_max-tempScan.angle_min)/(ranges.size()-1);//這個要注意
        tempScan.scan_time=(float)scan_time;                                                //單位s
        tempScan.time_increment=scan_time/(ranges.size()-1);                               //這個是變化的
        
        tempScan.range_min=0.15;
        tempScan.range_max=6.0;
        
        tempScan.ranges.resize(ranges.size());
        tempScan.intensities.resize(ranges.size());

        //填充雷達數據,判斷填充的是否正確
        for(size_t i=0;i<ranges.size();++i)
        {
            tempScan.ranges[i]=ranges[i];
            tempScan.intensities[i]=15.0;//這個可能沒用
        }

        //===========================================================================
        #if debug_
        //封裝數據的可視化的測試
        std::vector<double> angles_temp,ranges_temp;
        for(int i = 0; i < tempScan.ranges.size();i++)
        {
            double lidar_dist = tempScan.ranges[i];
            double lidar_angle = tempScan.angle_min + tempScan.angle_increment * i;

            ranges_temp.push_back(lidar_dist);
            angles_temp.push_back(lidar_angle);
        }
        visual_cloud_scan(ranges_temp,angles_temp,255,255,255);
        #endif
        //===========================================================================
        //發佈
        scan_pub_.publish(tempScan);
    }

    //使用點雲將激光可視化
    #if debug_
    void visual_cloud_scan(const std::vector<double> &ranges_,const std::vector<double> &angles_,unsigned char r_,unsigned char g_,unsigned char b_)
    {
        unsigned char r = r_, g = g_, b = b_; //變量不要重名 
        for(int i = 0; i < ranges_.size();i++)
        {
            if(ranges_[i] < 0.05 || std::isnan(ranges_[i]) || std::isinf(ranges_[i]))
                continue;

            pcl::PointXYZRGB pt;
            pt.x = ranges_[i] * cos(angles_[i]);
            pt.y = ranges_[i] * sin(angles_[i]);
            pt.z = 1.0;

            // pack r/g/b into rgb
            unsigned int rgb = ((unsigned int)r << 16 | (unsigned int)g << 8 | (unsigned int)b);
            pt.rgb = *reinterpret_cast<float*>(&rgb);

            visual_cloud_.push_back(pt);
        }        
    }
    #endif 
    /**
     * @name getLaserPose()
     * @brief 得到機器人在里程計座標系中的位姿tf::Pose
     *        得到dt時刻激光雷達在odom座標系的位姿odom_pose
     * @param odom_pos  機器人的位姿
     * @param dt        dt時刻
     * @param tf_
    */
    bool getLaserPose(tf::Stamped<tf::Pose> &odom_pose,
                      ros::Time dt,
                      tf::TransformListener * tf_)
    {
        odom_pose.setIdentity();

        tf::Stamped < tf::Pose > robot_pose;
        robot_pose.setIdentity();
        robot_pose.frame_id_ = scan_frame_name_;//這裏是laser_link
        robot_pose.stamp_ = dt;                 //設置爲ros::Time()表示返回最近的轉換關係

        // get the global pose of the robot
        try
        {   //解決時間不同步問題
            if(!tf_->waitForTransform(odom_name_, scan_frame_name_, dt, ros::Duration(0.5)))             // 0.15s 的時間可以修改
            {
                ROS_ERROR("LidarMotion-Can not Wait Transform()");
                return false;
            }
            tf_->transformPose(odom_name_, robot_pose, odom_pose);
        }
        catch (tf::LookupException& ex)
        {
            ROS_ERROR("LidarMotion: No Transform available Error looking up robot pose: %s\n", ex.what());
            return false;
        }
        catch (tf::ConnectivityException& ex)
        {
            ROS_ERROR("LidarMotion: Connectivity Error looking up looking up robot pose: %s\n", ex.what());
            return false;
        }
        catch (tf::ExtrapolationException& ex)
        {
            ROS_ERROR("LidarMotion: Extrapolation Error looking up looking up robot pose: %s\n", ex.what());
            return false;
        }

        return true;
    }

    /**
     * @brief Lidar_MotionCalibration
     *        在分段時刻的,激光雷達運動畸變去除;
     *        在此分段函數中,認爲機器人是勻速運動;
     * @param frame_base_pose       標定完畢之後的基準座標系
     * @param frame_start_pose      本分段第一個激光點對應的位姿
     * @param frame_end_pose        本分段最後一個激光點對應的位姿
     * @param ranges                激光數據--距離
     * @param angles                激光數據--角度
     * @param startIndex            本分段第一個激光點在激光幀中的下標
     * @param beam_number           本分段的激光點數量
     */
    void Lidar_MotionCalibration(
            tf::Stamped<tf::Pose> frame_base_pose,//對於每一幀scan,基準座標系一致
            tf::Stamped<tf::Pose> frame_start_pose,
            tf::Stamped<tf::Pose> frame_end_pose,
            std::vector<double>& ranges,
            std::vector<double>& angles,
            int startIndex,  //每一個分段的激光點起始序號
            int& beam_number)//此分段中,激光點的個數
    {
        //每個位姿進行線性插值時的步長
        double beam_step = 1.0 / (beam_number-1);

        //機器人的起始角度 和 最終角度,四元數表示
        tf::Quaternion start_angle_q =   frame_start_pose.getRotation();
        tf::Quaternion   end_angle_q =   frame_end_pose.getRotation();

        //轉換到弧度
        double start_angle_r = tf::getYaw(start_angle_q);
        double base_angle_r = tf::getYaw(frame_base_pose.getRotation());

        //機器人的起始位姿
        tf::Vector3 start_pos = frame_start_pose.getOrigin();//Ps
        start_pos.setZ(0);

        //最終位姿
        tf::Vector3 end_pos = frame_end_pose.getOrigin();    //Pe
        end_pos.setZ(0);

        //基礎座標系
        tf::Vector3 base_pos = frame_base_pose.getOrigin();
        base_pos.setZ(0);

        double mid_angle;
        tf::Vector3 mid_pos;
        tf::Vector3 mid_point;

        double lidar_angle, lidar_dist;
        //插值計算出來每個點對應的位姿
        for(int i = 0; i< beam_number;i++)
        {
            //得到該激光點的角度插值,線性插值需要步長、起始和結束數據
            mid_angle =  tf::getYaw(start_angle_q.slerp(end_angle_q, beam_step * i));

            //得到該激光點的里程計位姿線性插值
            mid_pos = start_pos.lerp(end_pos, beam_step * i);

            //得到激光點在odom 座標系中的座標 根據
            double tmp_angle;

            //如果激光雷達不等於無窮,則需要進行矯正.//首先讀數據進行判斷
            if( tfFuzzyZero(ranges[startIndex + i]) == false)
            {
                //計算對應的激光點在odom座標系中的座標

                //得到這幀激光束距離和夾角
                lidar_dist  =  ranges[startIndex+i];
                lidar_angle =  angles[startIndex+i];

                //在激光雷達座標系下激光點的座標
                double laser_x,laser_y;
                laser_x = lidar_dist * cos(lidar_angle);
                laser_y = lidar_dist * sin(lidar_angle);

                //在對應的里程計座標系下激光點的座標
                double odom_x,odom_y;
                odom_x = laser_x * cos(mid_angle) - laser_y * sin(mid_angle) + mid_pos.x();
                odom_y = laser_x * sin(mid_angle) + laser_y * cos(mid_angle) + mid_pos.y();

                //轉換到類型中去
                mid_point.setValue(odom_x, odom_y, 0);
                //得到在基準座標系下激光點的座標
                //把在odom座標系中的激光數據點 轉換到 基礎座標系
                //得到那一瞬時,應該測得的激光點的數據
                double x0,y0,a0,s,c;
                x0 = base_pos.x();
                y0 = base_pos.y();
                a0 = base_angle_r;
                s = sin(a0);
                c = cos(a0);
                /*
                 * 把base轉換到odom 爲[c -s x0;
                 *                     s  c y0;
                 *                     0  0 1 ]
                 * 把odom轉換到base爲 [c s -x0*c - y0*s;
                 *                    -s c  x0*s - y0*c;
                 *                     0 0  1          ]
                 */
                double tmp_x,tmp_y;
                tmp_x =  mid_point.x()*c  + mid_point.y()*s - x0*c - y0*s;
                tmp_y = -mid_point.x()*s  + mid_point.y()*c  + x0*s - y0*c;
                mid_point.setValue(tmp_x,tmp_y,0);

                //然後計算該激光點以起始座標爲起點的 dist angle
                double dx,dy;
                dx = (mid_point.x());
                dy = (mid_point.y());
                lidar_dist = sqrt(dx*dx + dy*dy);
                lidar_angle = atan2(dy,dx);

                //激光雷達被矯正
                ranges[startIndex+i] = lidar_dist;
                angles[startIndex+i] = lidar_angle;
            }
            //如果等於無窮,則隨便計算一下角度
            else
            {
                //激光角度
                lidar_angle = angles[startIndex+i];

                //里程計座標系的角度
                tmp_angle = mid_angle + lidar_angle;
                tmp_angle = tfNormalizeAngle(tmp_angle);

                //如果數據非法 則只需要設置角度就可以了。把角度換算成start_pos座標系內的角度
                lidar_angle = tfNormalizeAngle(tmp_angle - start_angle_r);

                angles[startIndex+i] = lidar_angle;
            }
        }
    }

    //激光雷達數據 分段線性進行插值 分段的週期爲5ms,可以更改
    //這裏會調用Lidar_MotionCalibration()
    /**
     * @name Lidar_Calibration()
     * @brief 激光雷達數據 分段線性進行差值 分段的週期爲5ms
     * @param ranges 激光束的距離值集合
     * @param angle 激光束的角度值集合
     * @param startTime 第一束激光的時間戳
     * @param endTime 最後一束激光的時間戳
     * @param *tf_
    */
    void Lidar_Calibration(std::vector<double>& ranges,
                           std::vector<double>& angles,
                           ros::Time startTime,
                           ros::Time endTime,
                           tf::TransformListener * tf_)
    {
        //統計激光束的數量
        int beamNumber = ranges.size();
        if(beamNumber != angles.size())
        {
            ROS_ERROR("Error:ranges not match to the angles");
            return ;
        }

        // 5000us來進行分段
        int interpolation_time_duration = 5 * 1000;//單位us

        tf::Stamped<tf::Pose> frame_base_pose;
        tf::Stamped<tf::Pose> frame_start_pose;
        tf::Stamped<tf::Pose> frame_mid_pose;
        tf::Stamped<tf::Pose> frame_end_pose;

        //起始時間 us
        double start_time = startTime.toSec() * 1000 * 1000;    //轉化單位爲us
        double end_time = endTime.toSec() * 1000 * 1000;
        double time_inc = (end_time - start_time) / beamNumber; // 每束激光數據的時間間隔,單位us

        //當前插值的段的起始座標
        int start_index = 0;

        //起始點的位姿 這裏要得到起始點位置的原因是 起始點就是我們的base_pose
        //所有的激光點的基準位姿都會改成我們的base_pose
        
        //得到t時刻激光雷達在odom座標系的位姿frame_start_pose、frame_end_pose
        if(!getLaserPose(frame_start_pose, ros::Time(start_time /1000000.0), tf_))
        {
            ROS_WARN("Not Start Pose,Can not Calib");
            return ;
        }

        if(!getLaserPose(frame_end_pose,ros::Time(end_time / 1000000.0),tf_))
        {
            ROS_WARN("Not End Pose, Can not Calib");
            return ;
        }
        //計數報錯使用
        int cnt = 0;
        //基準座標就是第一個位姿的座標
        frame_base_pose = frame_start_pose;
        for(int i = 0; i < beamNumber; i++)
        {
            //分段線性,時間段的大小爲interpolation_time_duration=5000us
            double mid_time = start_time + time_inc * (i - start_index);//這裏的mid_time、start_time多次重複利用
            if(mid_time - start_time > interpolation_time_duration || (i == beamNumber - 1))
            {
                cnt++;
                //得到臨時終點frame_mid_pose在里程計中的位姿,對應一個激光束
                if(!getLaserPose(frame_mid_pose, ros::Time(mid_time/1000000.0), tf_))
                {
                    ROS_ERROR("Mid %d Pose Error",cnt);
                    return ;
                }
                //對當前的起點和終點進行插值
                //interpolation_time_duration分段間隔中間有多少個點,算上本分段間隔首尾
                int interp_count = i - start_index + 1;//可以嘗試推算一下,通常會有幾十個或者上百個激光點
                //對本分段的激光點進行運動畸變的去除
                Lidar_MotionCalibration(frame_base_pose,
                                        frame_start_pose,
                                        frame_mid_pose,
                                        ranges,
                                        angles,
                                        start_index,
                                        interp_count);

                //更新時間
                start_time = mid_time;
                start_index = i;     //爲了方便計算分段中激光點個數
                frame_start_pose = frame_mid_pose;
            }
        }
    }

public:
    //聲明TF的聆聽者、ROS句柄、scan的訂閱者、scan的發佈者
    tf::TransformListener* tf_;
    ros::NodeHandle nh_;
    ros::Subscriber scan_sub_;
    ros::Publisher  scan_pub_;

    //針對各自的情況需要更改的名字,自行更改
    const std::string scan_frame_name_="laser_link";
    const std::string odom_name_="odom";
    const std::string scan_sub_name_="scan";
    const std::string scan_pub_name_="scan_cal";

    #if debug_
    //可視化點雲對象
    pcl::PointCloud<pcl::PointXYZRGB> visual_cloud_;
    #endif
};

int main(int argc,char ** argv)
{
    ros::init(argc,argv,"LidarMotionCalib");

    tf::TransformListener tf(ros::Duration(10.0));

    LidarMotionCalibrator tmpLidarMotionCalib(&tf);

    ros::spin();
    return 0;
}


在這裏插入圖片描述

發表評論
所有評論
還沒有人評論,想成為第一個評論的人麼? 請在上方評論欄輸入並且點擊發布.
相關文章