THE routine inclusion of multimodal sensing systems inautonomous vehicles and robotics platform is inevitable. Multimodal information improves the reliability and accuracy of many aspects of robotics such as robotic perception, autonomous navigation, dense mapping and localisation as a result of the complementary characteristics of each sensing modality [1]–[3], [21]. Two of the most important complementary sensing modalities on robotics platforms are LiDARs and visual cameras. A LiDAR provides three-dimensional geometric information while a visual camera represents twodimensional appearance information.
In order to effectively integrate information (spatially and temporally) obtained from multiple sensing modalities, it is essential to represent them in a common reference frame. Spatial alignment (i.e., extrinsic calibration) is the process of estimating the relative six degree of freedom (6DoF) transformation (i.e., rotation and translation) between different sensor coordinate systems. Time synchronization is the process
Manuscript received: September, 10, 2019; Revised December, 2, 2019; Accepted January, 8, 2020.
This paper was recommended for publication by Editor Eric Marchand upon evaluation of the Associate Editor and Reviewers’ comments.
Chanoh Park, Peyman Moghadam are with the Robotics and Autonomous Systems, DATA61, CSIRO, Brisbane, QLD 4069, Australia and the School of Electrical Engineering and Robotics, Queensland University of Technology (QUT), Brisbane, Australia. E-mails: Chanoh.Park,
Sridha Sridharan, Clinton Fookes are with the School of Electrical Engineering and Robotics, Queensland University of Technology (QUT), Brisbane, Australia. E-mails: chanoh.park, peyman.moghadam,
Soohwan Kim is with Division of Smart Automotive Engineering, Sun Moon University, South Korea, E-mail: kimsoohwan@gmail.com
of estimating any time offset and delay between the different sensing systems.
The problem of estimation of the rigid body transformation between the multimodal sensory information (camera and LiDAR) has been extensively studied in the past two decades [1], [4]–[6]. Despite recent developments, fusing multimodal sensory information is still a challenging problem [7]. Previously proposed solutions can provide a reasonable estimation of these parameters but they are limited due to their offline processing requirement [8] and a dedicated artificial calibration target present in a controlled environment [9].
In real-world robotic applications, the LiDAR and the camera can be separately located on moving parts of vehicles (semi-rigid), with little or no overlapping field of view and the extrinsic parameters could continuously change, requiring the ability for running calibration routines on-the-fly. As a result, the target-based method cannot be utilized. There are methods that do not require a calibration target [1], [7], however, these methods assume special geometry of the scene (e.g., lines, planes and points) which are generally only applicable to controlled environments (i.e., indoor). Furthermore, time synchronization is often ignored in many prior works. The effect of a small time difference resulting either from time lag or time delay is considerably huge in hand-held 3D sensor payloads where the angular velocity is usually very high [10].
To overcome these problems, we propose a targetless, structureless method for LiDAR and visible camera spatiotemporal calibration. Our proposed method has no assumptions about the sensor configurations or parameter initial guesses. The proposed method is composed of two stages. The first stage provides a rough closed-form solution for the extrinsic parameters of the unknown system as well as a rough time lag estimation. During the second stage, the spatiotemporal parameters are refined by the proposed structureless continuous-time structure-from-motion model. Due to the structureless approach where the 3D structures are purely constructed from images, there is no requirement to have an overlapping Field of View (FOV) between sensors. We demonstrate that the proposed method is capable of acquiring an accurate estimate of the spatiotemporal parameters on different platforms with multiple sensor payload configurations.
The extrinsic calibration between LiDAR and visible cameras has long been studied in robotics. The calibration methods can be grouped into two major categories: target based and targetless. Target based methods utilize a dedicated, artificial calibration target to be observed simultaneously from LiDAR and visible cameras. Zhang [11] firstly utilized a planner checkerboard for the extrinsic calibration where normal directions are extracted from a LiDAR point cloud and its corresponding 3D pose is extracted from the 2D image of the checkerboard. Three pairs of normal directions and checkerboard poses are enough to calculate the extrinsic parameters. By identifying multiple co-planner 3D positions from 3D pointclouds, Guindel et al. [12] reduced the minimum number of data required for calibration. Many other variations of target based methods [8], [13] have been proposed to address the limitations of the Zhang [11] method, however, due to their requirement of dedicated artificial target objects for calibration, they are not suitable for in-situ calibration where such a calibration target is not available.
Targetless approaches use natural geometrical features around the scanning area to estimate the extrinsic parameters. Moghadam et al. [1] utilized the projected 3D line segments on a 2D image in a typical indoor environment. Their method extracts 3D lines from a point cloud and finds matched 2D line segments on the image. Then, matched pairs of line segments are utilized in the pose optimization. Rehder et al. [7] utilized a RANSAC based planer object extraction method. Their method extracts three and more planes from the point cloud and utilizes them for the calibration. However, both methods are limited to a place where such geometrical features are available (i.e., indoor environment).
Many of the targetless approaches utilize mutual information to determine the rigid transformation between the coordinate frames. Napier et al. [14] applied a mutual information based registration technique to the camera-LiDAR calibration problem. Their method finds the extrinsic parameters that maximizes the mutual information between the intensity edge image of the projected LiDAR point cloud and the image edge pattern. Similarly, Gaurav et al. [15] and Zachary et al. [16] use mutual information based on raw intensity values and the projected normal point cloud image. More recently, Miled et al. [17] proposed a joint 2D histogram based mutual information calculation. However, mutual information based approaches are computationally expensive and are not suitable for a temporal calibration. Furthermore, the approach in this category is only available when enough of a view overlap exists between the camera and LiDAR.
Temporal calibration is also an important part of multimodal sensor fusion but is often not addressed in previous literature for the reason that many of the systems are either aiming for static scanning [16] or short-term operation [18]. However, in many practical applications in robotics, the system continuously receives asynchronous estimations from LiDAR and a not connected or unsynchronised visible camera while in motion [12]. This is especially the case for hand-held systems where the angular velocity is rapidly changing. Even a small time lag can result in a considerable misalignment between multimodal sensing systems.
Most of the extrinsic calibration approaches above, except [1], [7], ignores the temporal alignment. Temporal calibration is relatively more complicated than extrinsic calibration as asynchronous measurements should be considered. Redher et al. [7] addressed the problem by introducing a continuous-time trajectory [19]. However, their method is limited to an
Fig. 1. Block Diagram of the proposed spatiotemporal camera-LiDAR calibration system.
initial calibration or batch offline processing only. Some of the recent research [20] proposed to use a dedicated hardware for the synchronization but a hardware system is not cost efficient and is platform dependent.
In this section we overview our spatiotemproal calibration method for LiDAR and camera sensory systems as depicted in Fig. 1. In the first stage of the proposed method, the closed-form solution of the extrinsic is found by the odometry of each sensor. The time stamps of each trajectory are roughly synchronized by detecting a moment where the sensory set starts to move. We assume that the trajectory of each sensor is estimated independently from the observation of each sensor e.g., LiDAR trajectory from point cloud registration [21] and camera trajectory from visual odometry by images [22]. In the second stage, the extrinsic and time lag parameters are refined by reducing the 3D-2D projection error where the 3D locations of each 2D features are calculated from triangulation rather than projecting 3D LiDAR points onto 2D images or vice versa.
In this section, we describe our coarse-to-fine approach for spatiotemporal camera-LiDAR calibration.
A. Continuous-Time Trajectory Representation
Before presenting the details of our calibration method, we briefly explain the continuous-time trajectory representation which models a pose T as a function of time
,
where R and t
denote the rotation matrix and translation vector, respectively. The simplest way to model a continuous-time trajectory is linear interpolation on the manifold. Given two discrete poses T
at time
, the pose at time
can be interpolated as,
where the relative pose T
and the interpolation ratio
.
Throughout the rest of this paper, we denote a continuous-time pose as and a discrete-time pose as
, where the superscript and subscript represent their reference and body coordinate systems respectively.
Fig. 2. A continuous-time trajectory representation for a LiDAR and a camera system. The camera poses are specified at discrete times
, while the LiDAR poses
are modeled with a continuous-time trajectory T
The reference world frame, LiDAR frame and camera frame are represented as w, L, and C respectively.
B. Coarse camera-LiDAR Extrinsic Parameter Estimation
The proposed method utilizes the motion of each sensor to find the rough extrinsic parameters. Thus, we assume that the motion of each sensor is estimated by LiDAR odometry and visual odometry. Then, from each trajectory we extract a set of relative transformations and utilize them for the extrinsic calibration.
Given a pair of relative transformations in the LiDAR coordinate frame and a pair of relative transformations in the camera coordinate frame, we show that it is possible to calculate the LiDAR to camera transformation with a closed-form solution. In this coarse stage, we assume that the two trajectories are roughly synchronized, which we will further discuss in the experiment section.
Fig. 2 depicts a continuous-time trajectory for a system with a LiDAR and a camera. Note that a LiDAR sensor provides continuous observations, while a global-shutter camera produces discrete ones. Thus, the system trajectory is modeled with a continuous-time trajectory in the LiDAR coordinates and parameterized with discrete poses T.
Suppose that two camera poses up to scale at times
are given. Then, the relative camera pose is,
where the scale factor is introduced for monocular camera scale ambiguity. On the other hand, let us query the corresponding LiDAR poses
from the estimated continuous-time trajectory. Note that the LiDAR trajectory reference frame w and the camera reference frame
is not identical. Then, the relative LiDAR pose is,
Assuming that the camera is mounted on the same platform as the LiDAR system, the relative poses are constrained as,
where the camera-LiDAR extrinsic parameters to estimate are,
Note that the AX = XB in Eq. (5) is often noted as the hand-eye calibration [23].
Fig. 3. The projection errors e-th 3D visual feature
i-th image frame are used to find the camera-LiDAR extrinsic parameters
and time lag
Substituting Eq. (3), (4) and (6) into Eq. (5) gives,
The solution to Eq. (7) can be found by aligning correspondences in the manifold. Let Rbe the conversion from a rotation matrix to a canonical representation for k pairs of camera-LiDAR relative poses. Then, its covariance is defined as,
By Singular Value Decomposition, the rotation matrix can be found by decomposing the covariance matrix as,
Given the rotation, the translation and scale factor can be found by solving the following linear equation,
Note, that at least three relative pose pairs (k > 3) are required for the uniquely defined solution. Also, making an adequate amount of roll, pitch, yaw motion is important to estimate the parameters with a sufficient accuracy. The effect of motion will be investigated in Section V.
C. Refined Extrinsic and Time Lag Estimation
The close-form, coarse extrinsic estimation in the previous section reduces an algebraic distance rather than the geometric error. Thus, once the rough extrinsic parameters are obtained as a closed-form solution, we refine it jointly with the time lag estimation using non-linear optimization.
Fig. 3 describes the projection errors of visual features. Suppose that the 3D position of a visual feature is initialized by triangulation of 2D image features. Then, the error between the j-th feature location on the i-th image frame
and its projection onto the i-th image frame is,
Fig. 4. Sensing Configurations: [left]: Hand-held, [middle]: Vehicle, [right]: legged robot used for the spatiotemporal calibration. Two common LiDAR sensors (highlighted in red) are used (UTM-30LX, VLP-16). The added camera (highlighted in green) is an independent camera system and does not share a common clock with the LiDAR.
where denotes the extrinsics,
represents the time lag of the LiDAR sensor, and
stands for the camera projection.
We find the optimal parameters x which minimizes the following objective function,
where denotes a weight matrix of M-estimators. To find the optimal solution iteratively, we apply the GaussNewton algorithm with its approximated hessian and gradient,
where J is the Jacobian of the objective function,
is the concatenated weights, and b is the error of the current iteration. Then, the increment is computed as,
and is iteratively added to the current state as x x on the manifold.
D. Structureless Optimization Update
For the efficiency of estimation, we introduce the stuctureless approach, where we marginalize the 3D points from the state estimation. First, we divide the state to be estimated as the essential part and the part to be marginalized,
where are the extrinsics and time lag and
are the set of 3D points to be marginalized. Then, we can decompose the Eq. (15) into two parts as,
Then, we apply the Schur complement to marginalize the subset of variables,
Finally, the marginalized increment is given by solving the following linear equation,
Fig. 5. Screenshots of the datasets in Table I. (a) to (d): different environments, (e): no view overlap, (f) to (g): different platforms and baseline lengths.
Fig. 6. Rotation error of the closed-form solution with various simulated motions. The higher motions in roll, pitch and yaw directions produce the more accurate rotation estimations for various sample and noise cases. The unit of y-axis is the angular vector norm.
The structure part should be recalculated for each iteration [24]. It is also possible to estimate the time lag only by further marginalizing the extrinsic parameters.
In this section, we present quantitative and qualitative per- formance analysis of the proposed method with both simulated and real data in different sensor configurations. In particular, we compare the accuracy of the closed-form solution in the coarse stage with the optimized solution in the refinement stage. Comparison of the proposed method on different types of environment are presented.
A. Experiment Setup
Fig. 4 illustrates multiple camera-LiDAR sensor configura-tions mounted on hand-held, vehicle and legged robot used for our experiments. We have used two common LiDAR sensors, highlighted in red, (UTM-30LX, VLP-16). The added camera (highlighted in green) is an independent camera system and does not share a common clock with the LiDAR. Video recording is manually triggered by an operator which yields an unknown initial time lag.
For the real data experiment, we recorded multiple datasets (Fig. 5) in different environments and with different sensor payload configurations. The dataset (a) to (d) were recorded in multiple environments with the same hand-held single beam LiDAR setup (Fig. 4 left). In the dataset (e), the camera and LiDAR were pointing in the opposite direction which is presented to demonstrate the ability of the calibration where the camera and LiDAR do not share a view at all. For the demonstration of the proposed method on various robotics platforms with different baseline lengths, the dataset (f) to (h) were collected with a handheld device with a longer-baseline (f), vehicle (g), and a legged robot(h) as shown in Fig. 4 middle and right. The multi-beam LiDAR is utilized for the dataset (f) to (h).
B. Closed-Form Solution in the Coarse Stage
1) Experiments with Simulated Data: In the first experi-
ment, we evaluate the accuracy of the estimated rotational part of the extrinsic parameters based on how many relative pose samples between camera-LiDAR are needed as well as the amount of variations required to excite relative poses between two time stamps.
The experiment in Fig. 6 shows that the most dominant component is the amount of motion in the relative pose but this did not improve after some point (around 30 degrees). Also, the more number of samples after 15 did not significantly improve the accuracy of the rotation parameter estimation. With the higher noise level (line with circles) the overall rotation estimation is more noisier but showed the similar pattern. Based on this observation we utilized 10 relative pose samples for the experiment with the real data in the next section. Also, we made the motion larger than 25 degrees.
2) Experiments with Real Data: We also performed exper-
iments with real data to evaluate the accuracy of the close-form solution for estimating extrinsic parameters. The mono camera trajectories were estimated by visual odometry [22], while the continuous-time trajectory of the LiDAR sensor were estimated by our previous work [2], [21]. Prior to the closed-form solution calculation, two trajectories are roughly synchronized automatically by detecting the start of the motion using the rotation velocity of the LiDAR trajectory and mean feature movement in the 2D image space as depicted in Fig. 7. The amount of the time lag estimation error in the coarse stage is given in Table I row. We assumed that the LiDAR motion distortion is compensated in the odometry estimation [2].
The first row of Table I summarizes the accuracy in extrinsic parameter estimation with different types of real datasets where each estimation is compared to the ground-truth. The
Fig. 7. Example of initial time synchronization by detecting the start of the motion. This rough synchronization is enough for generating a reasonable initial guess on the extrinsic as given in Table II.
Fig. 8. [left]: Simulated trajectory with 3D features, [right]: Noise corrupted 2D features in the image space and corresponding 3D projected points after calibration.
ground-truth extrinsic parameters for quantitative evaluation are obtained by manually selecting 3D points from the LiDAR point cloud and their corresponding 2D points in images. A non-linear least square optimization is used to minimize the projected distance between the 3D and 2D points and to obtain the ground-truth. We validated the ground-truth estimation visually over multiple frames across time. The ground-truth time lag is estimated by the global time lag optimization method in [18] and is manually verified.
Table II shows how the synchronization error affects the accuracy of coarse extrinsic parameter estimation by introducing artificial time lag between two sensing modalities. Results suggest that the extrinsic parameter estimation in the coarse stage is less sensitive to relatively high time lag (0.5 sec) while being able to estimate good enough initial guesses for the refinement stage.
C. Extrinsic and Time Lag Estimation in the Refinement Stage
1) Experiments with Simulated Data: As the exact ground-
truth for extrinsic parameters and time lag estimation in real datasets are often unknown, we performed simulated experiments to demonstrate the accuracy of the proposed refinement stage. As shown in Fig. 8, we simulated a camera with a resolution of 1280720 at 20 Hz. We mimicked a hand-held motion for the system trajectory and introduced a Gaussian noise of
pixels to the projected visual feature locations. The same extrinsic values of the real device are utilized with an extrinsic error that are randomly generated according to the expected error variance of the close-form solution. The time lag is set within 10 milliseconds. We repeated the experiment 50 times with random trajectories and results are summarized in Table III. The test is repeated with different numbers of frames. Frames are evenly selected over the entire trajectory.
The experiment shows that with more number of frames included a better accuracy is achieved as well as prevent-
TABLE I CALIBRATION ACCURACY ACCORDING TO ENVIRONMENT
Comparison of the spatiotemporal calibration error on multiple datasets from different environments. ) coarse and
) refine represent the extrinsic estimation error respectively for before and after the refinement.
represents the difference between initial time lag estimated by the method in Fig. 7 and refined time lag. The unit of the baseline length is in meters.
stands for the rotational error in radians with
for the translational error in meters,
for the time lag error in milliseconds.
Fig. 9. Qualitative comparison of accuracy between different methods. For each method, the blend of the captured image and normal map is shown on the left, while the center area is enlarged on the right.
TABLE II ACCURACY ACCORDING TO THE TIME LAG
Effect of the synchronization error in the coarse stage. stands for the rotational error in radians with
for the translational error in meters.
TABLE III ACCURACY ACCORDING TO THE NUMBER OF FRAMES USED
The errors (means and variances) in optimally estimated extrinsic parameters and time lag with the simulated data in Fig. 8. The errors decrease as more frames are added to the optimization. stands for the rotational error in radians with
for the translational error in meters,
time lag error in milliseconds.
ing the chance of having a trajectory that does not have enough coverage of roll, pitch, yaw. But additional frames increases computational complexity. Selection of the frame number should be differentiated according to the angular and linear velocity of the trajectory that will be utilized for the calibration. Based on the simulation result in Table III, we have utilized 10-30 key frames for the hand-held and robot mounted experiments in the next section.
2) Experiments with Real Data: The estimated extrinsic
parameters are further refined with the proposed continuous-time structureless bundle adjustment. For the proposed iterative optimization method, 2D features are tracked by KLT [25] and only 30 distinctive frames are utilized to estimate the spatiotemporal parameters. Outliers are rejected by the Mestimator. To prevent a sub-optimal result due to the initial synchronization error, only the time lag is refined in the beginning by marginalizing the extrinsic and structure from the state. Then, the extrinsic is jointly optimized with the time lag after updating the image time stamps. The extrinsic is updated by the closed-form solution before the joint estimation. The same process of obtaining the ground-truth for extrinsic parameters in the coarse stage is used for the refinement stage.
The comparison of the extrinsic calibration result between the different state-of-the-art methods is given in Table V, along with the visual comparison in Fig. 9. For a comparison, closed-form solution by a normal trajectory segment [26], target-based calibration method [9], and refined extrinsic parameters are utilized. The qualitative comparison in Fig. 9 shows that the image to point cloud alignment is most accurate when it is refined.
TABLE IV ROBUSTNESS AGAINST THE TIME LAG
Robustness against the time lag in estimating spatiotemporal parameters. Utilized camera records in 30 frame per second where frame interval is around 33ms. stands for the rotational error in radians with
translational error in meters,
for the time lag error in milliseconds.
The extrinsic estimation error after the refinement is given in the second row of Table I. As the proposed method does not require any shared geometric features between the LiDAR and camera, the method works at various types of places ((a),(b) outdoor, (c) indoor, (b),(d) place with lack of geometrical features) and configurations ((e) single beam LiDAR without view overlap). Also, the experiment result with a longer baseline (f) showed a similar performance. The result in (g), (h) indicates that the proposed method is suitable for the on-wake-up self-calibration on a legged robot and a vehicle (Fig. 4 (a) [middle, right]).
The time lag error after the refinement stage could not be evaluated as the accuracy of the ground-truth estimation method [18] is in a similar range to that of our refinement stage. This is due to the fact that in the method time lag and extrinsic cannot be jointly estimated. The ground-truth estimation of the extrinsic parameters are not affected by the time lag if a stationary key frame is used whereas the opposite is not true. Instead, we provide a video1 that qualitatively demonstrates the temporal alignment quality.
The time lag calibration of above is only valid within the utilized image frames. Since, the time lag continuously changes, the time lag should be tracked on-the-fly. The result in Table IV demonstrates such ability of the proposed method without the dedicated sensor motion. In this stage, we only run the refinement operation without the first stage. For the experiment, the randomly selected five trajectory segments which were extracted from a normal hand-held motion with three seconds length and 30 key frames are utilized. The motion speeds are 0.7 rad/s and 0.9 m/s. The result in Table IV implies that the proposed method was able to estimate the parameters even with relatively large time lags without effecting the extrinsic parameters.
Some of the detailed scenes are presented in Fig. 10 using the estimated spatiotemporal parameters to show the camera and LiDAR alignment quality by blend of the captured images and the projected surfel clouds colored by the normal directions.
The translation estimation error ratio is relatively higher with the short baseline setups. Given the other experiments with the longer baseline shows the similar error range, it is
TABLE V CALIBRATION ACCURACY COMPARISON
Accuracy comparison with different methods. Manually tuned extrinsic parameters and time lag are utilized as ground-truth. stands for the rotational error in radians with
for the translational error in meters.
Fig. 10. (left): captured images, (middle): surfel clouds projected on the image, (right): blend of the captured images and projected surfel clouds. The color in the surfel clouds represents normal directions.
reasonable to assume that the 0.5 to 4cm error in translation estimation is the estimation accuracy lower bound with our sensor setup and estimation uncertainty in feature tracking and LiDAR trajectory.
The comparison of the extrinsic estimation in the coarse and refinement stage suggests that conventional motion-based only methods yields relatively high uncertainty in rotation estimation. It is due to the fact that even a small rotational motion is amplified in the refinement stage by being projected on the image and therefore rotation is more observable during the optimization.
The extrinsic estimation of the dataset (a) to (d) has been performed with the identical sensor setup at the different environments. The mean and standard deviation of the rotation and translation error after the refinement is 4.0(1.6)radian and 0.017(0.012) meters respectively with the standard deviation in () whereas the coarse stage shows 13.1(12.7)
radian and 0.019(0.007) meters respectively. This implies that the proposed refinement stage is able to provide robust estimation of the extrinsic parameters regardless of the environment.
A. Limitation and Future works
While the proposed method is flexible, it has a couple of practical limitations.
Time lag estimation: the time lag parameter is not observable when the platform is stationary. Time lag uncertainty grows during the stationary mode. Thus, for a system with an independent camera, this could be problematic when the platform resumes to move after a long period of time.
Dedicated motion: while in many robotic platforms, such as legged robots, it is easier to move for calibration, there are platforms where it is not easy to do so. For example, with the vehicle type platform it is not easy to make adequate motion in a short time. Also, the proposed method requires 3D geometrical features and trackable visual features to exist in the scene. The lack of these geometrical features can cause localization slips in LiDAR odometry estimation which affects the accuracy of the calibration result. The lack of trackable visual features presents a similar issue. Thus, observability test and input data analysis that judge if the collected data is enough to carry out the calibration should be further studied for practical application.
In this paper, we proposed a spatiotemporal calibration method for a camera-LiDAR system. The proposed method provides an efficient way for camera-LiDAR calibration without a dedicated calibration target or view alignment. This is achieved by introducing a structureless refinement stage where the key advantage is that 3D points for reprojection are being calculated only from triangulation of 2D features, therefore, the proposed method does not require a known target or view alignment between the LiDAR and camera for matching features. Also, the coarse stage provides a close enough spatiotemporal initial guess which prevents the refinement stage from failure or getting stuck in a local minima. Through the experiments, we demonstrated the utility of the method on various robotics platforms and scenarios. While the proposed method is more flexible than existing solutions, the results illustrate a decent accuracy for the point cloud colorization under situations where trackable and stable visual patterns exist in the view.
The authors gratefully acknowledge funding of the project by the CSIRO and QUT. Support from several members of the CSIRO Robotics and Autonomous Systems including Tam Benjamin, Gavin Catt and Mark Cox are greatly appreciated.
[1] P. Moghadam, M. Bosse, and R. Zlot, “Line-based extrinsic calibration of range and image sensors,” in International Conference on Robotics and Automation (ICRA), May 2013, pp. 3685–3691.
[2] C. Park, S. Kim, P. Moghadam, J. Guo, S. Sridharan, and C. Fookes, “Robust photogeometric localization over time for map-centric loop closure,” IEEE Robotics and Automation Letters, vol. 4, no. 2, pp. 1768– 1775, April 2019.
[3] P. Moghadam, W. S. Wijesoma, and D. J. Feng, “Improving path planning and mapping based on stereo vision and lidar,” in 10th International Conference on Control, Automation, Robotics and Vision, 2008, pp. 384–389.
[4] J. Kang and N. L. Doh, “Automatic targetless camera–lidar calibration by aligning edge with gaussian mixture model,” Journal of Field Robotics, 2019.
[5] S. Vidas, P. Moghadam, and M. Bosse, “3D thermal mapping of building interiors using an RGB-D and thermal camera,” in 2013 IEEE International Conference on Robotics and Automation, 2013, pp. 2311– 2318.
[6] J. Jeong, Y. Cho, and A. Kim, “The road is enough! extrinsic calibration of non-overlapping stereo camera and lidar using road information,” IEEE Robotics and Automation Letters, vol. 4, no. 3, pp. 2831–2838, 2019.
[7] J. Rehder, P. Beardsley, R. Siegwart, and P. Furgale, “Spatio-temporal laser to visual/inertial calibration with applications to hand-held, large scale scanning,” in International Conference on Robotics and Automation (ICRA). IEEE, 2014, pp. 459–465.
[8] S. Sim, J. Sock, and K. Kwak, “Indirect Correspondence-Based Robust Extrinsic Calibration of LiDAR and Camera,” Sensors, vol. 16, no. 6, p. 933, June 2016.
[9] K. M. Ahmad Yousef, B. J. Mohd, K. Al-Widyan, and T. Hayajneh, “Ex- trinsic Calibration of Camera and 2D Laser Sensors without Overlap,” Sensors, vol. 17, no. 10, Oct. 2017.
[10] C. Park, S. Kim, P. Moghadam, C. Fookes, and S. Sridharan, “Probabilis- tic Surfel Fusion for Dense LiDAR Mapping,” International Conference on Computer Vision Workshops (ICCVW), pp. 2418–2426, 2017.
[11] Q. Zhang and R. Pless, “Extrinsic calibration of a camera and laser range finder (improves camera calibration),” in International Conference on Intelligent Robots and Systems (IROS), vol. 3, Sept. 2004, pp. 2301– 2306 vol.3.
[12] C. Guindel, J. Beltr´an, D. Mart´ın, and F. Garc´ıa, “Automatic extrinsic calibration for lidar-stereo vehicle sensor setups,” in International Conference on Intelligent Transportation Systems (ITSC), Oct. 2017, pp. 1–6.
[13] Y. Park, S. Yun, C. S. Won, K. Cho, K. Um, and S. Sim, “Calibration between Color Camera and 3D LIDAR Instruments with a Polygonal Planar Board,” Sensors, vol. 14, no. 3, pp. 5333–5353, Mar. 2014.
[14] A. Napier, P. Corke, and P. Newman, “Cross-calibration of push-broom 2D LIDARs and cameras in natural scenes,” in International Conference on Robotics and Automation (ICRA), May 2013, pp. 3679–3684.
[15] G. Pandey, J. R. McBride, S. Savarese, and R. M. Eustice, “Automatic Extrinsic Calibration of Vision and Lidar by Maximizing Mutual Information,” J. Field Robot., vol. 32, no. 5, pp. 696–722, Aug. 2015.
[16] Z. Taylor and J. Nieto, “A mutual information approach to automatic calibration of camera and lidar in natural environments,” in Australian Conference on Robotics and Automation, 2012, pp. 3–5.
[17] M. Mourad, S. Bahman, H. Emmanuel, and V. Bruno, “Hybrid online mobile laser scanner calibration through image alignment by mutual information,” ISPRS Annals of Photogrammetry, Remote Sensing and Spatial Information Sciences, vol. 3 (1), pp. 25-31, 2016.
[18] P. Vechersky, M. Cox, P. Borges, and T. Lowe, “Colourising point clouds using independent cameras,” IEEE Robotics and Automation Letters, vol. 3, no. 4, pp. 3575–3582, 2018.
[19] M. Bosse and R. Zlot, “Continuous 3D scan-matching with a spinning 2D laser,” in International Conference on Robotics and Automation (ICRA), May 2009, pp. 4312–4319.
[20] H. Sommer, R. Khanna, I. Gilitschenski, Z. Taylor, R. Siegwart, and J. Nieto, “A low-cost system for high-rate, high-accuracy temporal calibration for LIDARs and cameras,” in International Conference on Intelligent Robots and Systems (IROS), Sept. 2017, pp. 2219–2226.
[21] C. Park, P. Moghadam, S. Kim, A. Elfes, C. Fookes, and S. Sridharan, “Elastic LiDAR Fusion: Dense Map-Centric Continuous-Time SLAM,” in International Conference on Robotics and Automation (ICRA), 2018, pp. 1–8.
[22] R. Mur-Artal, J. M. M. Montiel, and J. D. Tard´os, “ORB-SLAM: A Versatile and Accurate Monocular SLAM System,” IEEE Transactions on Robotics, vol. 31, no. 5, pp. 1147–1163, Oct. 2015.
[23] Q. Ma, Z. Goh, S. Ruan, and G. S. Chirikjian, “Probabilistic approaches Autonomous Robots, pp. 1–24, Apr. 2018.
[24] B. Triggs, P. F. McLauchlan, R. I. Hartley, and A. W. Fitzgibbon, “Bundle Adjustment — A Modern Synthesis,” in Vision Algorithms: Theory and Practice, ser. Lecture Notes in Computer Science. Springer, Berlin, Heidelberg, Sept. 1999, pp. 298–372.
[25] C. Tomasi and T. Kanade, “Detection and Tracking of Point Features,” International Journal of Computer Vision, Tech. Rep., 1991.
[26] Z. Taylor and J. Nieto, “Motion-Based Calibration of Multimodal Sensor Extrinsics and Timing Offset Estimation,” IEEE Transactions on Robotics, vol. 32, no. 5, pp. 1215–1229, Oct. 2016.