Keywords

1 Introduction

As human civilization and technology improved by leaps and bounds, cars have played an important role in daily life, which is indispensable for the society. The attached problems like traffic safety, congestion and energy consumption have also been intensively studied. Developing automatic driving technology has become an indispensable way to improve transportation efficiency and relieve congestion.

The autonomous driving map is a key concern of autonomous vehicles. In the existing function modules of intelligent connected vehicles, autonomous driving map is not only used to support macro-lane-level path planning [1], but also provides accurate prior information for local trajectory planning [2], working as a prerequisite for active map-based positioning [3]. Compared with the traditional navigation map, autonomous driving map is characterized by precise and complete information description, which the surrounding environment information can be catched accurately and reliably, and the cost of environmental perception be reduced effectively. It is crucial for autonomous driving. In order to achieving high precision positioning using point clouds, accurate pose estimation and multi-source information association are two core problems.

Simultaneous localization and mapping (SLAM) refers to the situation when autonomous cars are located in a thoroughly unexplored scenario, moving in an unknown environment while proceeding incremental mapping of the environment. The interconnection between localization and constitution causes complexity to the SLAM problem. The accurate positioning of autonomous driving relays on the map which includes the consistency of the surrounding environment. Similarly, the construction of a highly consistent environment map is based on the premise of positioning with accurateness as well [4]. SLAM can be divided into laser SLAM and visual SLAM. Visual sensor can be applied to indoor and outdoor environment, and visual sensor can perceive and obtain rich environmental information in use. Many scholars have carried out research on visual SLAM, but visual sensor has the disadvantage of being easily interfered by light. In contrast, lidar is not affected by light and has high robustness. Up to now, lidar-based real-time positioning and mapping is still a popular technology in autonomous driving [5].

In real traffic scenes, the characteristics of road conventional traffic scenes are quite different from those of tunnels. Tunnels are usually constructed of artificial materials and may possess several kilometers’ length, which are characterized by lack of geometric structure and may cause degradation to the point cloud. Accurate positioning and environment map construction, path planning and motion control are the key technologies to improve the reliability and intelligence degree of autonomous driving in diversified scenes. Path planning and obstacle avoidance require environmental map and precise positioning. In order to guarantying vehicles are able to obtain accurate environmental maps in most scenes, it is significant to explore the mapping effects of different cloud map generation algorithms in different traffic scenes. The analytic result may contribute to improving the positioning accuracy and the robustness of autonomous driving.

Most studies are based on conventional roads using a single algorithm, and few studies have touched upon the performance comparison of different approaches for constructing point cloud maps. This paper collects point cloud data of conventional roads and tunnels bases on lidar. NDT algorithm uses probability model to match by calculating probability density rather than matching the features of points, SC-LeGO-LOAM added loopback detection based on Scan Context on the basis of LeGO-LOAM, the features of lines and surfaces are matched in the calculation [6]. These two algorithms belong to two different registration modes. Therefore, NDT algorithm and SC-LeGO-LOAM algorithm are used to make point cloud maps of conventional roads and tunnels, respectively. By comparing the production effects of the two algorithms in the same environment, the above two algorithms are objectively analyzed. The poor mapping effect in the scene of tunnel where lacking geometric structure and degenerated point cloud of NDT algorithm has showed in the experimental results. Comparatively, SC-LeGO-LOAM can get a better mapping effect.

The frame of this paper is as follows. The second segment introduces the registration of traditional point cloud algorithms Iterative Closest Point (ICP) and NDT. After theoretical analysis of ICP and NDT algorithms, NDT algorithm is selected as one of the algorithms in this experiment. Section 3 introduces Lidar Odometry and Mapping (LOAM), Lightweight and Ground-optimized Lidar Odometry and Mapping (LeGO-LOAM) and SC-LeGO-LOAM, where SC-LeGO-LOAM is selected as one of the algorithms in this paper. In the fourth section, NDT algorithm and SC-LeGO-LOAM algorithm are selected into experimental platform, and the above two algorithms are used to make point cloud maps for the conventional road and off-campus tunnel environment. The above two algorithms are analyzed through the making effect of point cloud map. The summary of this work is given in Sect. 5.

2 Traditional Point Cloud Mapping Algorithm

2.1 ICP Algorithm

ICP is the point cloud registration algorithm. the correspondence of points set is determined first, and the optimal transformation of rigid body is calculated repeatedly until the convergence condition is satisfied, which is essentially the optimal matching based on the least square method [7]. The primary target of ICP is to solve the spatial transformation between source P and target Q in the overlapping region across two data sets, which is aimed at minimizing the distance between of P and Q [8]. Let E (R, t) be the objective function. The error of source P and target Q under the transformation matrix (R, t), which is expressed by E (R, t). where R is the rotation matrix and t is the translation matrix [9]. Then the optimal transformation matrix can be transformed into the optimal solution (R, t) satisfying minE(R, t) as following formula:

$$E\left(R,t\right)={\varSigma }_{i=1}^{n}{\Vert {Q}_{i}\cdot R+t\Vert }^{2}$$
(1)

The optimal transformation matrix is obtained under minimizing the objective function. The explicit step is illustrated following:

  1. 1.

    Each nearest point in source is calculated into the target;

  2. 2.

    Use the Singular Value Decomposition (SVD) to calculate the rotation matrix R and shift matrix T and minimize the objective function E (R, t);

  3. 3.

    Calculating rotation matrix R and translation matrix T to rotate and translate the point set P into the new corresponding points set Pʹ is obtained;

  4. 4.

    Calculating the average distance d between the new points set Pʹ and the objective points cloud Q:

    $$d=\frac{1}{n}{\varSigma }_{i=1}^{n}\| {P}_{i}^{{\prime}}-{Q}_{i}\| $$
    (2)
  5. 5.

    Set a maximum iteration, calculate the average distance D under the limitation of maximum iteration until it satisfies the threshold or the iterations reach the pre-defined number.

2.2 NDT Algorithm

NDT is a statistical model. If a set of random vectors satisfies a normal distribution, the probability density function [10] as expressing as follows:

$$P\left(x\right)=\frac{1}{{\left(2\pi \right)}^\frac{D}{2}\sqrt{\left|\varSigma \right|}}e\frac{{\left(x-\overrightarrow{u}\right)}^{T}{\varSigma }^{-1}\left(x-\overrightarrow{\mu }\right)}{{\left(2\sigma \right)}^{2}}$$
(3)

where D is the dimension, \(\overrightarrow{\mu }\) is the mean vector, Σ is the covariance matrix of the random vector. NDT algorithm can describe the scattering of point cloud by way of probability, which can effectively reduce the time required for registration [11]. The explicit step of algorithm is illustrated in following steps:

  1. 1.

    The point of target is scattered to each grid. The space where the laser point cloud is located is rasterized by a cube so that the laser point cloud is located in the corresponding cube;

  2. 2.

    Scattering the objective points cloud, then normal distribution probability density function in each grid is calculated subsequently. It is generally guaranteed that there are at least 5 points in the grid to avoid unsuitable sizes;

  3. 3.

    The initial coordinate transformation parameters of source points are determined with respect to objective point; This step provides the initial value close to the optimal value for the next iteration of transformation parameters;

  4. 4.

    The source point cloud performs the initial transformation of coordinate, then calculates the probability in the target grid. According to the (R, t) computed precedently, the coordinates of the source point cloud are converted to the objective grid. The converted source point cloud gets coordinated corresponding to the normal distribution probability density function of each voxel grid, then the probability of laser point coordinates after transformation is calculated.

  5. 5.

    The probability product of each point cloud is taken as the target likelihood function. The likelihood function with the maximum probability product is the optimal coordinate transformation, as shown in the equation:

$$ -{log}\,\varphi =-{\varSigma }_{k=1}^{n}\mathit{log}\left(P\left({X}^{{\prime}}\right)\right)$$
(4)

where −logφ is the negative logarithm form of the maximum likelihood function, which is used to facilitate the derivation later. Finally, the Newton iteration schema is used to acquire the optimal transformation parameters to complete point cloud registration.

2.3 Comparation of ICP Algorithm and NDT Algorithm

ICP, the algorithm that able to get registration precisely and effectly. It processes the data of points without feature extraction and segmentation. It can exhibit a good convergence ability with a good initial value. Compared with NDT algorithm, algorithm of ICP spends a large quantity of calculation on finding quantities of interrelated points, and the convergence region is small; the running speed is thus slow. Meanwhile, seeking the ICP algorithm adopts the assumption that the distance of Euclidean which can be obtained from the nearest point is corresponding to the point, which may result in wrong corresponding points. Comparably, the NDT algorithm has better robustness and an improved efficiency [12]. Therefore, this paper chooses NDT algorithm as one of the point cloud mapping algorithms.

3 Point Cloud Mapping Base on SC-LeGO-LOAM

SC-LeGO-LOAM adds loopback detection based on the Scan Context on the basis of LeGO-LOAM. Scan Context with the loopback detection, which was proposed from KAIST University in Korea, the author named Giseop Kim and Ayoung Kim [13]. The global descriptor with the main feature of non-histogram is proposed to help search “context” (current/previous data) in a quick and effective manner. Scan Context, for localization using a single 3D scan is an advanced spatial descriptor with a matching algorithm.

3.1 LOAM

LOAM is a 3D laser SLAM algorithm proposed by Ji Zhang et al., school of Robotics, Carnegie Mellon University, which has a good performance and ranks in the top of the accuracy of KITTI [14] odometer list. LOAM algorithm is a real time, low drift laser odometer and mapping method. LOAM divides the scanning and matching process of the laser odometer into two parts to recognize the relationship between point clouds at different moments. The high-frequency part adopts the “scanning-scanning” matching method and the low-frequency part adopts the “scanning-map” matching method. By using these two parts together, LOAM makes better use of computing resources and balance the problem of computing accuracy and efficiency. Figure 1 illustrates the system framework of LOAM.

Fig. 1.
figure 1

Flow diagram of LOAM algorithm system

Meanwhile, LOAM uses curvature features to registrate the point cloud which get from the Lidar. Traditional point cloud registration method is based on ICP. Generally, these methods can obtain better precision theoretically, but the calculation process consumes a lot of time, LOAM selects points with large curvature as edge points and points with small curvature as plane points, By calculating the interconnection between edge points and the interrelated edge, together with the interconnection between plane points and the interrelated plane, the position and pose transformation relationship of two-point cloud is established.The amount of points can be reduce effectively involved in the operation while ensuring accuracy by using LOAM.

3.2 LeGO-LOAM

LeGO-LOAM is an algorithm optimized and improved by TixiaoShan et al. on the basis of LOAM [15]. Because there are sundry objects on the ground, the accuracy of point cloud map may be affected if the point features on the ground in LOAM cannot meet the actual requirements. LeGO-LOAM introduces point cloud segmentation on the basis of LOAM to separate ground information and then carries out subsequent processing such as feature extraction for the segmented information. Different from LOAM, LeGO-LOAM introduces two-step LM optimization [16], which first optimizes plane point feature pairs in vertical direction, roll direction and pitch direction, and then optimizes edge points and other directions. The calculation budget is less than that of LOAM. And loopback detection mechanism is added and the graph optimization is used in LeGO-LOAM, LeGO-LOAM has a higher practical value. The system architecture of LeGO-LOAM is shown in Fig. 2. Due to the limitation of lidar hardware frequency, the neighboring frame clouds often differ greatly when the vehicle is moving fast. In order to overcome the problem that the scanning effect of laser odometer is poor when the position changes sharply, more high-frequency information is generally introduced as the initial value of scanning matching.

Fig. 2.
figure 2

Flow chart of LeGO_LOAM system

3.3 SC-LeGO-LOAM

It is necessary to solve the problems of descriptor rotation invariance and noise processing in lidar localization. First, the rotation invariance of descriptor does not change with changing viewpoints. Secondly, normals are lot of uncertain noisy due to the resolution of point cloud is easily fluctuate with distance, and noise processing is an unavoidable problem. At present, the mainstream approach is to use histogram to solve the two problems mentioned above. Considering the histogram method can only provide the random index of the surrounding environment, it cannot describe the detailed structure of the scene quickly and effectively, descriptors have some problems such as potential false positives and poor differentiability for location recognition.

The design method encodes all point clouds in 3d scanning as a matrix, and describes self-centered 2.5D information. Its main characteristics include:

  • The encoding function of efficient bin. On the premise of point cloud density and normal invariance, the bin encoding function is used to identify the position more efficiently [13, 17].

  • The internal structure of point cloud is preserved. Point cloud of bin determines the value of each element of the matrix. If the relative geometry of a point is described as a histogram [18], the absolute position of the point is lost. Therefore, by avoiding the adoption of histogram to preserve the complete inside structure of point cloud, the method aligns the viewpoints of query scan with candidate scan and improves the discrimination ability.

  • Efficient two-stage matching algorithm. Scan Context provides a rotating invariant descriptor by searching the first nearest neighbor, and combines the rotating invariant descriptor with pairwise comparability score at the level. This operation helps avoiding cyclic detection in all databases, it can thus obtain a viable search time.

4 Experimental Evaluation

So as to validate the effectiveness of NDT algorithm and SC-LeGO-LOAM algorithm in making point cloud map under different traffic scenarios, a large number of real vehicle multi-scene data have been collected. The hardware environment of the experiment is Intel i7 processor with 16 GB memory, and the system environment is a laptop installed with Ubuntu18.04 and Ros Melodic robot operating system. The experimental platform is The Great Wall VV6 vehicle (as shown in Fig. 3), and a single 64-line mechanical lidar OS1-64 is installed on the car roof. The experimental environments were conventional driveway in campus and Luntou tunnel in Guangzhou.

Fig. 3.
figure 3

The experimental platform

After collecting data in different scenes, NDT algorithm and SC-LeGO-LOAM algorithm are implemented to make point cloud map separately. Figure 4 shows the point cloud map made by NDT algorithm for conventional roads on campus.

Fig. 4.
figure 4

Point cloud map made by NDT algorithm for conventional road

As it illustrated in Fig. 4, NDT algorithm can clearly reconstruct the contour of conventional roads with dense point clouds. Figure 5 shows the point cloud map made by SC-LeGO-LOAM algorithm for conventional roads on campus.

Fig. 5.
figure 5

Point cloud map made by SC-LeGO-LOAM algorithm for conventional road

As given in Fig. 5, SC-LeGO-LOAM algorithm can reproduce the contour of conventional lanes on campus. Compared with Fig. 4, the point cloud in Fig. 5 is relatively sparse due to its high filter. Figure 6 shows the point cloud map of Luntou Tunnel in Guangzhou made by NDT algorithm.

Fig. 6.
figure 6

Point cloud map of tunnel in Guangzhou made by NDT algorithm

As illustrated from Fig. 6 that the tunnel point cloud map made by NDT algorithm could not clearly reconstruct the contour of the tunnel, and serious double shadow and noise appeared. Figure 7 shows the tunnel point cloud map made by SC-LeGO-LOAM.

Fig. 7.
figure 7

Point cloud map of tunnel made by SC-LeGO-LOAM algorithm

Figure 7 shows that compared with NDT algorithm, SC-LeGO-LOAM algorithm holds better point cloud map in tunnel scenes and can clearly reproduce the outline of the tunnel. Figure 4 and Fig. 5 shows that both NDT algorithm and SC-LeGO-LOAM algorithm can clearly show the outline of the conventional road. Tables 1 and 2 list the specific data of the above four groups of point cloud maps.

Table 1. Campus driveway
Table 2. Luntou Tunnel in Guangzhou

5 Conclusion

This paper explores the effect of different point cloud registration algorithm in heterogeneous traffic scenarios. Firstly, the required experimental scenes are selected, and the experimental data acquisition platform and data processing platform are constructed, which are based on the actual requirements of the scene and experiment. A great amount of laser point cloud data is collected using lidar mounted on real vehicles in real traffic environments. In the comparative analysis towards the traditional mapping algorithm, NDT algorithm is selected as one of the experimental algorithms in this paper, and the NDT algorithm and SC-LeGO-LOAM algorithm are used to make the point cloud maps of campus conventional lanes and tunnels.

Based on the actual point cloud mapping effect, it can be concluded that in conventional roads, both NDT algorithm and SC-LeGO-LOAM can clearly reproduce the outline of the road, and have a good mapping effect. In the scene of tunnel lacking of geometric structure and point cloud degradation like tunnels, NDT algorithm cannot make point cloud map and the cartographic effect is poor. Possible criteria can be obtained in this work to guide the algorithm determination task for making point cloud maps.