Next Article in Journal
A Novel Numerical Method for Theoretical Tire Model Simulation
Previous Article in Journal
A Vehicle Comparison and Re-Identification System Based on Residual Network
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

An Alpha/Beta Radiation Mapping Method Using Simultaneous Localization and Mapping for Nuclear Power Plants

1
College of Electrical and Power Engineering, Taiyuan University of Technology, Taiyuan 030024, China
2
China Institute for Radiation Protection, Taiyuan 030024, China
*
Author to whom correspondence should be addressed.
Machines 2022, 10(9), 800; https://doi.org/10.3390/machines10090800
Submission received: 29 July 2022 / Revised: 6 September 2022 / Accepted: 7 September 2022 / Published: 11 September 2022
(This article belongs to the Section Robotics, Mechatronics and Intelligent Machines)

Abstract

:
Nuclear safety has always been a focal point in the field of nuclear applications. Mobile robots carrying specific sensors for nuclear-radiation detection have become an alternative to manual detection. This work presents an autonomous α/β radiation mapping framework, using a mobile robot carrying a light detection and ranging (LiDAR) and a nuclear-radiation-detection sensor. The method employs simultaneous localization and mapping (SLAM) techniques and radiation-detection sensors. Cartographer is adopted as a demonstration example to map the unknown environment. Radiation data are obtained through the radiation detection sensor and projected onto the environment map after coordinate alignment. The color-coded radiation map is shown on the environment map according to the dose rate. The simulation and real-environment experiments in a robot-operating system (ROS) validate the effectiveness of the proposed method in different radiation scenarios for both indoor and outdoor environments.

1. Introduction

The threat of nuclear leakage is growing as nuclear energy becomes more widely used in the new energy-generation field. Quantification of radiation dose in and around a nuclear facility (radiation mapping) is crucial. Thanks to advances in robotics and the increasing concerns about human and environmental safety [1], using robots carrying radiation-detection sensors has become a promising alternative to manual detection, as it avoids human exposure to radiation.
Different radiation-detection methods are used according to the types of radiation. There are two common types of radiation in nuclear applications: charged particles, such as α-rays, β-rays, and protons; and uncharged particles, such as X-rays, γ-rays, and neutrons. Currently, most of the detection of nuclear radiation is for X-rays and γ-rays [2], while there seems to be relatively little research on the detection of α/β radiation. Although α/β radiation is relatively easier to shield, both internal exposure from α-rays and external exposure from β-rays can cause substantial damage to the human body. In addition, the accurate detection of α/β radiation allows the location of the radiation source to be identified, thus avoiding radiation interference with the micro-components in the integrated circuit board. Detection for α/β radiation can be divided into three categories: direct detection, indirect detection, and scan detection [2].
Both direct and indirect measurement methods, mainly operated by humans in the potentially contaminated area, are unable to measure total regional radiation levels, and the accuracy of the measurements is hardly guaranteed. On the other hand, the scan-detection method, which achieves autonomous radiation detection by fixing a radiation detector to a mobile robot, has attracted attention in recent years [3]. Scan detection allows for better radiation detection due to the robot’s autonomous exploration capabilities. However, detecting the radiation intensity and its location and then projecting the results on an environment map for better man–machine interaction is still an open problem. SLAM is an effective technique to solve this problem.
In the absence of a priori environmental information, SLAM uses a robot carrying specific sensors to model the environment during motion, while estimating its motion [4]. SLAM has become one of the essential technologies for the autonomous localization and navigation of unmanned systems since it does not rely on satellite signals but only uses sensor information to achieve localization and navigation. An intuitive idea to achieve autonomous nuclear-radiation detection is to equip the robot with a radiation detector and build a map of the environment by using SLAM methods. The radiation-detection results are then aligned and fused with the scene map. Autonomous nuclear-radiation detection consists of two steps: scene map building and the fusion of radiation detection results with the scene map.
Scene mapping uses SLAM to represent information about the scene. Maps have different forms depending on their characteristics and applications, such as sparse-feature maps, point cloud maps, topological maps, and grid maps [5,6,7,8]. In order to enable the robot to navigate autonomously through the radiation environment, as well as follow a specified path to detect the radiation results, the prerequisite is to build a grid map of the radiation scene. The grid-map-building method was first proposed by Elfes [9]. The idea is to divide the entire working environment into homogeneous grids and propose the use of probabilities to indicate the likelihood of obstacles in each grid. The grid map plays an important role in numerous robotic applications such as localization [10], exploration [11], and mapping performance benchmarking [12]. The Gmapping algorithm is an open-source SLAM algorithm based on a filtering SLAM framework, which is also commonly used for grid map building [13]. The Gmapping algorithm is widely used to implement SLAM in robots with LiDAR and overcomes the disadvantages of particle dissipation of the RBPF algorithm [14]. Today, the most famous open-source SLAM algorithm is Cartographer, which was developed by Google [15]; it combines LiDAR and inertial measurement unit (IMU) data to generate a real-time two-dimensional grid map.
The projection of the radiation results on the scene map is essentially a multi-source-information-fusion problem. The basic principle is to make full use of multi-sensor observation information. According to certain criteria, the complementary information from multiple sensors is combined in space or time to obtain consistent information. Asharif et al. proposed the use of Bayes’s method and De Morgan’s rule in a grid map to accomplish the fusion of different sensor data [16]. Besada-Portas et al. proposed a delay estimation TDE algorithm for mobile chassis environment-aware sensor fusion [17]. This algorithm completes the data synchronization of all types of sensors according to the timestamp, thus ensuring the accuracy of all types of sensor inputs and the fused model. Krystian Chachuła et al. proposed an enhanced algorithm for multi-sensor data fusion that is used for the detection of pollutants in wastewater [18]. Kai et al. combined scene-data fusion (SDF) with localization and mapping (LAMP) to propose a method for imaging three-dimensional γ nuclear-radiation sources [19]. Manish K. Sharma et al. proposed a statistic-based grid-refinement method for backtracking the position of a γ-rays source in a three-dimensional domain in real time [20].
With regard to the location of different types of nuclear radioactive sources, researchers have been focusing on estimating the location of radioactive sources from radiation dose rates measured by nuclear-radiation detectors on mobile robots. Typical methods include the least-squares methods, maximum likelihood estimation methods, geometric methods, and Bayesian estimation algorithms [21,22,23,24]. These methods are good choices when it comes to X-rays and γ-rays since these rays can travel to a much farther distance compared to α/β radiation, and the detector has to determine the source location according to the radiation data.
The application of mobile robots to monitor radioactive areas has increased significantly since the Fukushima Daiichi nuclear power plant leak in 2011. Currently, most of the mobile robots that have been designed for radiological features of the Fukushima Daiichi nuclear power plant are applied for γ-rays detection. For instance, the JAEA-3 [25] and Quince [26] robots have been deployed for γ-rays monitoring at the Fukushima nuclear facility. The RICA robot was developed by the French Alternative Energy and Atomic Energy Commission and Cyberia France, which has also been deployed to operate nuclear facilities for γ-ray detection [27]. In addition, the Georgia Institute of Technology developed a suite of robots for detecting and locating embedded γ-rays and neutron sources [28]. However, research on mobile robots for α/β radiation detection is not yet sufficient. Though the CARMA robot developed by the University of Manchester in collaboration with Sellafield Site is capable of α/β radiation detection [29], the CARMA platform is only applicable to a small range of scenarios and cannot meet the needs of a large range of environments such as nuclear plants.
As α/β radiation dies out when it is even a few centimeters away from the radiation source, we can take the position where the radiation is detected as the location of the radiation source. So, different from the aforementioned work, this paper presents a mobile robot solution that can be used for autonomous detection of α/β radiation. In this study, the surface-contamination detector was equipped with a Turtlebot2 robot for α/β radiation monitoring. In particular, the surface-contamination detector is a self-developed radiation detector that can be used for surface-contamination monitoring [30]. In addition, the methodological framework proposed in this paper is also applicable to the X-rays/γ-rays environment if the appropriate sensor is utilized, meaning that, once the robot pose is obtained, we can always locate the source of radiation since we know the relative coordinate between the robot and the radiation detector when the hardware is designed.
This paper is organized as follows. Section 2 describes the hardware materials and method proposed in this paper. Section 3 presents the simulation and experiment results. The analysis of the results is also conducted in this section. Section 4 discusses the experimental details of this paper and its contributions. Section 5 concludes the paper.
The abbreviations used in this paper are listed in Table 1.

2. Materials and Methods

2.1. Hardware Materials

2.1.1. Robotics Platform

This study used Turtlebot2 as a vehicle for radiation detection and map building. Turtlebot2 is a robotic platform manufactured by Willow Garage, California, USA. Turtlebot2 is shown in Figure 1. It includes NVIDIA JETSON TX2, KOBUKI chassis.RPLiDAR A2 LiDAR, etc.
The Turtlebot2 is driven by KOBUKI and is equipped with a three-axis digital gyroscope, collision sensor, cliff sensor, and wheel encoder. KOBUKI is a robotic chassis from Yujin Robot that is widely used as a robot research platform. The odometry information is provided by the wheel encoder. The Turtlebot2 is equipped with the NVIDIA JETSON TX2, which is an embedded system developer module. The mobile robot platform is also equipped with LiDAR and a surface-contamination monitor. The LiDAR enables real-time distance and angle information to be measured between the mobile robot and its surrounding obstacles. This information is mainly used by the mobile robot for the creation of a two-dimensional grid map of the searching area and positioning and obstacle avoidance when it comes to autonomous navigation. The LiDAR used in this study is RPLiDAR A2, which has a maximum effective measuring distance of 40 m and an effective scanning angle of 360 degrees. The surface-contamination monitor used in this system was developed by the China Institute for Radiation Protection [30]. More detail is given in the next subsection.

2.1.2. Surface Contamination Monitor

The surface-contamination monitor used for radiation mapping is shown in Figure 2, and the main parameters are given in Table 2.
Figure 2 shows the construction of the surface-contamination monitor, which consists of a shell, photomultiplier tube, plastic, scintillator, and light-proof aluminum foil. The surface-contamination monitor operates at a distance of 0.5–1 cm from the ground, and the measurement mode is a two-channel counter, which measures α/β radiation dose values separately.
The detection principle is that, when α/β particles enter the sensitive zone of the composite scintillator, the particles interact with the respective sensitive detection media in the composite scintillator to produce light pulses of different amplitudes. The light-pulse signal is transformed into an electrical-pulse signal through the photomultiplier tube. After preprocessing by the signal-processing unit, the count rates of the α and β signals are recorded by the microcontroller system, and the detection results are then output.
In the radiation-detection process, when the α/β radiation-contamination area is smaller than the detector window area, the surface-contamination monitor is used to detect the contamination plane directly. The surface emissivity of the contaminated area and the surface activity of the contaminated area are calculated according to Equations (1) and (2):
q = N i N b R i  
A = Q × N i N b R i × S  
where q is the surface emissivity, with unit   ( s × 2 π sr ) 1 ; Ni is the average of the instrument’s dose rate, with unit s 1 ; Nb is the average of the instrument’s background measurements, with unit s 1 ; Ri is the surface emissivity response of the corresponding magnitude of the nuclide, with unit   Bq ; A is the surface activity, with unit Bq / cm 2 ; Q is the ratio of the standard surface activity to surface emissivity; and S is the area of the detection window of the surface contamination monitor, with unit cm 2 .
When the α/β radiation-contamination area is larger than the detector-window area, the effect of uneven contamination areas on the measurement results must be taken into account. The presence of inhomogeneous contaminated areas is determined by moving the detector to measure different contaminated areas. If the contaminated area is homogeneous, radiation detection is carried out directly by using a surface-contamination monitor. The surface emissivity of the contaminated area and the surface activity of the contaminated area are calculated according to Equations (3) and (4), respectively:
  q = ( N i - N b ) × S 1 R i × S    
A = Q × ( N i - N b ) × S 1 R i × S 2    
where S1 is the area of the contaminated area.
When the contaminated area is not homogeneous, the multi-point measurement method can be applied. After selecting different locations in the contaminated area for measurement and calculating the surface emissivity and surface activity at each point in the contaminated area according to Equations (3) and (4), the average of the results at each point is considered as the measurement of the contaminated area.

2.2. LiDAR SLAM

In this section, some common LiDAR SLAM algorithms are introduced. The basic process of LiDAR SLAM involves a mobile robot starting from any area in an unknown environment and building a map of the environment, while obtaining environmental information based on the LiDAR it carries. The SLAM problem can be formulated as follows:
p ( x 1 : k , m | z 1 : k , u k - 1 )  
where z 1 : k ,   u k - 1 represents the measurement from LiDAR and the control input, x 1 : k represents the pose of the robot from time 1 to time k, and   m   is the map built till time k.
The SLAM problem is an estimation problem. Based on the estimation theory employed, there are two categories of SLAM approaches: filter-based approaches and non-linear optimized approaches. The key technique of filter-based localization approaches is Bayesian filtering or its derivatives. Non-linear optimized approaches, mainly graph-optimization SLAM approaches, estimate the poses of the robot and landmarks of the environment to get the trajectory of the robot and the map of the environment. The cumulative error caused by various noises is eliminated by means of optimization.
On the other hand, the existing SLAM approaches can also be classified according to the sensor a robot carries. In fact, all of these approaches can be used to map the environment with specific premises considered. For instance, if a LiDAR sensor is only mounted on the robot, we can choose Cartographer, Gmapping, Karto_SLAM [31], and Hector_SLAM [32]. Furthermore, even for the same type of sensors, for example, if it is a single-line LiDAR, we can choose among Cartographer, Gmapping, Karto_SLAM, and Hector_SLAM. If it is a multi-line LiDAR, LOAM and its derivatives are a good choice. Considering the sensor that we currently mount on our robot, which is a single-line LiDAR, we aim to build a two-dimensional grid map. Thus, only Cartographer, Gmapping, Karto_SLAM, and Hector_SLAM were considered in the experiments.
Since Cartographer is well-known for its high mapping accuracy, we take Cartographer as a demonstration example for the proposed radiation-mapping method. The mapping process of the Cartographer can be divided into two parts: front end and back end, as shown in Figure 3. The sensor data are divided into LiDAR data, odometry data, and IMU data. The LiDAR data are preprocessed by a voxel filter to reduce the amount of LiDAR data, the IMU data are fused with the Odom data after the IMU tracker, and the fused data are transmitted to scan matching in the front end for positional interpolation. The front-end part accepts the processed sensor data and then performs the scan-matching process, which interpolates the current LiDAR data into the best position of the submap by matching the LiDAR data. The submap is continuously built with new LiDAR data being inserted. The front end treats the scan matching of local maps as a quadratic optimization problem, with the Ceres-solver solving the optimization problem. The back-end part contains the loop closure, which is implemented by using sparse pose adjustment (SPA) to eliminate matching errors between submaps. An important part of this process is the scan matching with the submap; this is performed by using the branch-and-bound scan matching (BBS) method, improving accuracy and speed considerably.
The main difference between Cartographer and other two-dimensional SLAM mapping algorithms is the use of submap in the scan-matching session. Whenever the scan data are obtained, they are matched with the most recently created submap, so that the LiDAR data of this scan can be inserted into the best position on the submap. The mapping process is run iteratively.
The poses of an autonomous mobile robot can be represented by ξ = ( ξ x , ξ y , ξ θ ) , with ξ x and ξ y representing translations in the x and y directions, respectively, and ξ θ representing rotations in the two-dimensional plane. The scan data are added to the submap coordinate system through Equation (6):
T ξ p = ( c o s ξ θ - s i n ξ θ s i n ξ θ c o s ξ θ ) p + ( ξ x ξ y )      
where T ξ represents the position pose transformation from the point cloud coordinate system to the corresponding submap coordinate system, which transforms the point p in the point cloud from the point cloud coordinate system to the submap coordinate system.
Cartographer represents the submap by using a probability grid; each pixel stores the probability value of the occupied grid point. The occupancy probability values are updated according to the pose of each map point in the submap coordinate system. The Ceres-based scan matcher calculates the pose of the LiDAR-scanned point cloud in the submap, which converts the pose solution to a nonlinear least-squares problem, which is expressed as Equation (7):
a r g m i n ξ k = 1 K ( 1 - M s m o o t h ( T ξ p ) ) 2  
where M s m o o t h represents a bicubic interpolation function.
Cartographer achieves accurate mapping of large scenes by creating a large number of submaps. The pose estimates obtained by scan matching between the current laser scan and multiple neighboring laser scans are reliable in a short period but accumulate incorrectly over time. Consequently, loop closure is implemented to reduce the cumulative error. Cartographer applies the branch and bound optimization method to reduce computational cost and improve real-time performance. The optimization problem can be described as follows:
a r g m a x ξ ω k = 1 K M n e a r e s t ( T ξ h k )  
where ω is a search window size, K is the last scan point, M n e a r e s t is the extension of the nearest grid point in M s m o o t h , and h k represents the LiDAR measurement data.

2.3. Methods

Map fusion is the main contribution of this work, which focuses on a grid map and radiation map fusion. Figure 4 illustrates the map fusion process framework. After building the scene map using the Cartographer algorithm, the robot can locate itself in the scene. The mobile robot carries a surface contamination monitor to detect radiation source data on the scene. The position of the radiation source in the scene is determined by means of a transform frame (TF)coordinate transformation relationship, which enables the radiation source to be located. When the radiation data are transmitted to the robot operating system (ROS) via the data interface, the radiation data and grid map are fused by means of data-fusion methods to obtain detailed information on the radiation scenes, as well as the map information.
In order to realize the map fusion of the environment map and the radiation data, the data communication interface that can receive the radiation data collected by the radiation sensor needs to be designed. In this communication setup, the sensor communication protocol is transmission control protocol/internet protocol (TCP/IP). Message interoperability is driven via a custom interface. Finally, when radiation information is detected, it is transmitted to ROS for algorithmic processing to complete the radiation-map building. Since different two-dimensional SLAM algorithms perform differently in their particular operating environment, we propose a framework for radiation mapping that is appropriate for the common two-dimensional SLAM. This framework allows the flexibility to switch algorithms depending on the environment in which two-dimensional SLAM is applicable.
The proposed map fusion approach takes reference from the Costmap approach [33], where the robot can obtain an all-around perception of the surrounding terrain’s state through this map. Costmap is a type of map that is attached to the robot. It uses the robot as the coordinate origin at all times and represents the navigation environment around the robot through the probability values of the grid map.
As shown in Figure 5, where the static layer is the static map of the scene, the obstacles layer is the obstacles detected by the LiDAR during the detection process, the radiation layer is the radiation map layer detected by the surface contamination monitor, and the global map is a layer superimposed from the three mentioned layers. The radiation layer is initially a blank Costmap, which has the same dimensions as the grid map generated by Cartographer. Afterward, the radiation values are tagged into the radiation layer based on the radiation data returned by the interface callback during the robot’s radiation detection. The radiation layers are superimposed on the global map for map fusion. During the detection process of the mobile robot, not only is radiation information added to the global map but also part of the obstacles is detected and updated to the obstacle layer. At the same time, the global map is updated with the obstacle layer.

2.4. System Modeling in ROS

This part is about modeling the robot system in ROS. The first step is the model construction of the Turtlebot2 robot. The modeling results are shown in Figure 6. The Turtlebot2 was equipped with LiDAR for grid-map building. Furthermore, the model of the surface-contamination monitor was completed based on the characteristics of the sensor, and the feasibility of the model was verified in ROS.
The model building process is shown in Figure 7. First of all, the physical parameters of the sensor are set and the sensor is modeled in Gazebo according to these parameters. Since the radiation sensor consists of eight detection windows, eight separate windows are added to the modeled robotics system. The communication interface described in Section 2.3 is set up for radiation data transmission.

3. Experiments

We conducted a group of experiments to verify the proposed method. Firstly, we tested four algorithms for two-dimensional SLAM on a public dataset and analyzed the performance of the four algorithms by using the EVO tool. Secondly, we completed the radiation mapping in a simulation environment, and the accuracy of the data detected by the radiation sensors was evaluated. Finally, we experimented with the abovementioned four two-dimensional SLAM algorithms in real-world scenarios and used Cartographer to build the radiation map in both indoor and outdoor environments.

3.1. Comparison of Different SLAM Methods on a Public Dataset

We evaluated the performance of the Cartographer by using the publicly available dataset MIT STATA [34], and its performance was compared with Gmapping, Karto_SLAM, and Hector_SLAM since they are all designed for two-dimensional mapping with single-line LiDAR.
This paper uses the EVO tool to analyze the accuracy of the map [35]. The EVO tool is often applied in SLAM to evaluate the performance and trajectory accuracy of systems. The absolute trajectory error is used to calculate the difference between the true value of the sensor pose and the estimated value of the SLAM system. The relative pose error is used to calculate the difference between the pose change within two time stamps. The mapping results of the four SLAM methods are shown in Figure 8. The comparison indicates that Cartographer builds the map with higher accuracy than Karto_SLAM and Hector_SLAM. Figure 9 demonstrates the absolute pose errors of the four SLAM methods in terms of RMSE, MEAN, MEDIAN, STD, MIN, MAX, and SSE, respectively. Table 3 shows the results of the absolute positional errors of the four SLAM methods.

3.2. Radiation-Map-Fusion Results in the Simulation Environment

The results of the robot’s map fusion during radiation detection are shown in Figure 10. The nuclear plant simulation environment used in Reference [36] was adopted, as shown in the Figure 10a,b. In this simulation environment, a single radiation source and multiple radiation sources are added to the simulation environment, respectively. The radiation-mapping results are shown in Figure 10c,d. Different radiation levels are set during the radiation-detection process, where green represents low-risk radiation, purple represents medium-risk radiation, and red represents high-risk radiation. From the map-fusion results, we can see that the proposed radiation-mapping method shows promising results for α/β radiation.
Radiation levels are indicated according to different doses of incoming α/β radiation and are thus shown in different colors on the radiation map. Real-time monitoring of the radiation distribution can be achieved during the robotic detection of radiation, as shown in Figure 11. Figure 11a shows the real-time scenes captured by a camera during the detection process, and Figure 11b shows the real-time radiation-detection results. At the same time, real-time radiation detection allows the robot to be remotely controlled for radiation detection, thus protecting human beings from radiation or radioactive sources. As shown Figure 10b, we implemented a color-coded radiation-map-construction method during the robot’s real-time radiation detection. We used different radiation cost values to distinguish radiation risk areas, where green represents low dose values, with a radiation interval of 5–2000 radiation dose values, and its radiation cost value is 102; purple represents medium dose values, with a radiation interval of 2000–4000 radiation dose values, and its radiation cost value is 58; and red represents high dose values, with a radiation interval of 4000–6000 radiation dose values, and its radiation cost value is 128. The differentiation of radiation intensity by color allows the riskiness of radiation areas to be effectively determined.
Figure 12 shows the error analysis of radiation data during radiation detection. This section shows the dose values for a single radiation source during the detection process in Figure 11b. Figure 12a shows a comparison between the measured radiation data and the true radiation data. The horizontal axis indicates the detection process over time, and the vertical axis shows the radiation dose values; the blue line is the true dose value, and the red is the actual radiation sensor detection value. Figure 12b shows the results of the radiation-detection error. The results implicate that the mobile robot detects radiation with high efficiency in the simulation environment, with a maximum error around ±0.7%, and the average error is 0.3%.

3.3. Radiation Map Fusion Results in the Real Environment

In addition to the simulation experiments, the radiation-mapping performance was also tested in the real environment. The test was conducted in both an indoor environment and an outdoor environment. The indoor environment is a long corridor in which Cartographer, Gmapping, Hector_SLAM, and Karto_SLAM were each tested separately. Figure 13a shows a scene from an indoor environment. Figure 13b–e show the map-construction results of the four SLAM methods, respectively. The fused mapping of the scene and radiation is shown in Figure 13f, where a single radiation source was set up for radiation mapping in an indoor environment, and the radiation-mapping result shows that the radiation source can be effectively located and detected. It is worth noting that the two-dimensional-grid map-building algorithm can be selected according to the size and complexity of the indoor environment, thus achieving higher building efficiency and accuracy in locating radiation sources.
The outdoor environment was a park located at Taiyuan University of Technology, as shown in Figure 14a. The scene-mapping results of Cartographer, Gmapping, Hector_SLAM, and Karto_SLAM are shown in Figure 14b–e, respectively. We can see that Hector_SLAM and Karto_SLAM build maps with a large drift in this environment. The reason is that these two SLAM methods have no advantage in larger outdoor scenarios. Figure 14f shows the results of the radiation mapping in the outdoor environment, where multiple radiation sources were set up to build a radiation map. We can see that the radiation sources can be located, and the radiation mapping result is displayed in different colors according to the level of radiation dose. With excellent performance in outdoor environments, Cartographer can accurately locate the radiation sources.
In the real environment, the mapping process is susceptible to a variety of errors. Therefore, choosing a suitable map-construction method can improve the localization accuracy of the radiation source. From the experimental results in Figure 13 and Figure 14, we can see that Cartographer has a more balanced performance indoors and outdoors, and this is the reason for its selection in this paper. However, it is worth noting that the other three grid-mapping algorithms mentioned in this paper have advantages in some environments; for example, Gmapping shows the best mapping performance when it comes to small scenes. Therefore, the choice of method for two-dimensional grid-map building is flexible. The mapping results show that Cartographer has an advantage in building maps in both indoor and outdoor environments and that the method proposed in this paper has gained a satisfactory performance for radiation mapping.

4. Discussion

The α/β radiation-mapping method proposed in this paper is based on the integration of SLAM methods with nuclear-radiation-detection sensors, providing new means to map and visualize nuclear radiation for a friendly human–robot integration. It enhances the accuracy, speed, and efficiency of many applications related to nuclear- and radioactive-material detection and mapping; performs the monitoring of nuclear-legacy sites and operational nuclear facilities; offers wider radiation protection (e.g., accelerator facilities); provides consequence management for both intentional and unintentional releases of radioactive material; and leads to the decommissioning of nuclear facilities.
We proposed a general framework for autonomous radiation mapping through the integration of SLAM techniques and radiation-detection sensors, such as surface-contamination monitors. In this work, the two-dimensional grid map was built by SLAM methods in ROS. Four SLAM methods, namely Gmapping, Hector_SLAM, Karto_SLAM, and Cartographer, were specifically implemented to showcase the LiDAR-based SLAM methods for radiation mapping. From Figure 8 and Figure 9, we can see that, in large-scale areas, Cartographer is more accurate than the other three methods; this is due to the fact that Cartographer uses loop-closure detection for position correction during the mapping process. Among these four SLAM algorithms, both Gmapping and Cartographer have odometry. They use the odometer data to calibrate the map and for localization. Hector_SLAM requires a high level of sensor accuracy, which is the main reason for the large drift in the experimental results. Karto_SLAM has an intermediate performance on public datasets; however, real experiments have a higher time complexity compared to Cartographer.
For the radiation-detection sensors, we adopted the surface-contamination monitor developed by the China Institute for Radiation Protection in the robot for α/β radiation detection. Accordingly, we designed the data communication interface so that the radiation data can be collected by the radiation sensor and fused with the grid map built by SLAM methods. The radiation-mapping process can be described as follows. Firstly, the radiation sensors acquire radiation-information data and transfer the acquired radiation data to ROS via TCP/IP. Secondly, the data are parsed in ROS, and the processed data are passed to the radiation-map-construction algorithm for radiation-map construction. At the same time, the radiation map is merged into the two-dimensional grid map built by a SLAM method to locate the radiation source.
A color-coded radiation map was presented wherein different colors indicate different levels of radiation, allowing for a more intuitive display of the radiation map. We conducted the experiments in both the simulated environment and the real environment to demonstrate the radiation-mapping performance in both a single-radiation-source environment and a multiple-radiation-sources environment. At the same time, the error analysis of the radiation data during the radiation-detection process shown in Figure 11 indicates a promising detection accuracy, with a maximum dose-detection error of around ±0.7% and an average dose-detection error of 0.3%.
In our current work, we demonstrated the feasibility of the proposed method for autonomous α/β radiation with SLAM techniques. Both the experiments in a simulation environment and actual environments show promising results for potential nuclear-radiation applications. However, more experiments need to be performed to test the performance in real nuclear-radiation scenarios; such experiments will be performed cooperatively with the China Institute for Radiation Protection in the near future. Moreover, we will work on expanding the framework for other types of radiation mapping, such as γ-rays.

5. Conclusions

This paper proposed a method that combines SLAM techniques with nuclear-radiation-detection sensors to address the drawbacks of traditional manual radiation detection. The main contribution of this paper is four-fold: (1) SLAM was adopted to achieve autonomous radiation detection; (2) a surface-contamination monitor developed by the China Institute for Radiation Protection was first adopted in a robot for α/β radiation detection; (3) a general radiation mapping framework was proposed for α/β radiation mapping, in which LiDAR-based SLAM methods were adopted to demonstrate the radiation-mapping performance; and (4) a color-coded radiation map was projected onto the environment map built by SLAM methods. The simulation and real-scene experiments verified the proposed method and showed a promising future in the applications of autonomous nuclear detection. In the future, more experiments need to be performed in real nuclear radiation scenarios so that the proposed method can be promoted for actual applications in nuclear plants or other places with potential nuclear leaks. Furthermore, our work will focus on extending this radiation-map-building method to highly radioactive particles, such as X/γ-rays, to obtain a flexible radiation-mapping platform for various nuclear radiations.

Author Contributions

Conceptualization, X.L., L.C. and Y.Y.; funding acquisition, L.C., X.X., G.Y. and Z.Z..; investigation, X.L. and L.C.; methodology, X.L.; project administration, L.C., X.X., G.Y. and Z.Z.; supervision, L.C.; validation, X.L.; writing—original draft, X.L.; writing—review and editing, L.C. All authors have read and agreed to the published version of the manuscript.

Funding

This research was funded by the National Natural Science Foundation China, grant numbers 62073232 and 61973226; Foundation for Scientific Cooperation and Exchanges of Shanxi Province, grand number 202104041101030; and the Natural Science Foundation of Shanxi Province, grant number 201901D211079.

Institutional Review Board Statement

Not applicable.

Data Availability Statement

Not applicable.

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Smith, R.; Cucco, E.; Fairbairn, C. Robotic Development for the Nuclear Environment: Challenges and Strategy. Robotics 2020, 9, 94. [Google Scholar] [CrossRef]
  2. Amgarou, K.; Herranz, M. State-of-the-art and challenges of non-destructive techniques for in-situ radiological characterization of nuclear facilities to be dismantled. Nucl. Eng. Technol. 2021, 53, 3491–3504. [Google Scholar] [CrossRef]
  3. Tsitsimpelis, I.; Taylor, C.J.; Lennox, B. A review of ground-based robotic systems for the characterization of nuclear environments. Prog. Nucl. Energy 2019, 111, 109–124. [Google Scholar] [CrossRef]
  4. Durrant-Whyte, H.; Bailey, T. Simultaneous localization and mapping: Part I. IEEE Robot. Autom. Mag. 2006, 13, 99–110. [Google Scholar] [CrossRef]
  5. Cheng, R.; Razani, R.; Ren, Y. S3net: 3d LiDAR sparse semantic segmentation network. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021. [Google Scholar]
  6. Lim, H.; Hwang, S.; Myung, H. ERASOR: Egocentric ratio of pseudo occupancy-based dynamic object removal for static 3D point cloud map building. IEEE Robot. Autom. Lett. 2021, 6, 2272–2279. [Google Scholar] [CrossRef]
  7. Wang, F.; Zhang, C.; Zhang, W.; Fang, C.; Xia, Y.; Liu, Y.; Dong, H. Object-Based Reliable Visual Navigation for Mobile Robot. Sensors 2022, 22, 2387. [Google Scholar] [CrossRef] [PubMed]
  8. Xiao, S.; Tan, X.; Wang, J. A simulated annealing algorithm and grid map-based UAV coverage path planning method for 3D reconstruction. Electronics 2021, 10, 853. [Google Scholar] [CrossRef]
  9. Moravec, H.; Elfes, A. High resolution maps from wide angle sonar. In Proceedings of the 1985 IEEE International Conference on Robotics and Automation (ICRA), St. Louis, MO, USA, 25–28 March 1985. [Google Scholar]
  10. Ge, G.; Zhang, Y.; Wang, W.; Jiang, Q.; Hu, L.; Wang, Y. Text-MCL: Autonomous Mobile Robot Localization in Similar Environment Using Text-Level Semantic Information. Machines 2022, 10, 169. [Google Scholar] [CrossRef]
  11. Chen, C.S.; Lin, C.J.; Lai, C.C.; Lin, S.Y. Velocity Estimation and Cost Map Generation for Dynamic Obstacle Avoidance of ROS Based AMR. Machines 2022, 10, 501. [Google Scholar] [CrossRef]
  12. Amigoni, F.; Castelli, V.; Luperto, M. Improving repeatability of experiments by automatic evaluation of SLAM algorithms. In Proceedings of the 2018 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Madrid, Spain, 1–5 October 2018. [Google Scholar] [CrossRef]
  13. Abdelrasoul, Y.; Saman, A.B.S.H.; Sebastian, P. A quantitative study of tuning ROS gmapping parameters and their effect on performing indoor 2D SLAM. In Proceedings of the 2016 2nd IEEE International Symposium on Robotics and Manufacturing Automation (ROMA), Ipoh, Malaysia, 25–27 September 2016; pp. 1–6. [Google Scholar] [CrossRef]
  14. Doucet, A.; Freitas, N.D.; Murphy, K. Rao-Blackwellised Particle Filtering for Dynamic Bayesian Networks. In Sequential Monte Carlo Methods in Practice; Springer: New York, NY, USA, 2001; pp. 499–515. [Google Scholar] [CrossRef]
  15. Hess, W.; Kohler, D.; Rapp, H.; Andor, D. Real-time loop closure in 2D LIDAR SLAM. In Proceedings of the 2016 IEEE International Conference on Robotics and Automation (ICRA), Stockholm, Sweden, 16–21 May 2016; pp. 1271–1278. [Google Scholar]
  16. Asharif, M.R.; Moshiri, B.; Hoseinnezhad, R. Sensor fusion by pseudo information measure: A mobile robot application. ISA Trans. 2002, 41, 283–301. [Google Scholar] [CrossRef]
  17. Besada-Portas, E.; Lopez-Orozco, J.A.; Besada, J. Multisensor fusion for linear control systems with asynchronous, Out-Of-Sequence and erroneous data. Autom. J. IFAC 2011, 47, 1399–1408. [Google Scholar] [CrossRef]
  18. Chachua, K.; Nowak, R.; Solano, F. Pollution Source Localization in Wastewater Networks. Sensors 2021, 21, 826. [Google Scholar] [CrossRef]
  19. Vetter, K.; Barnowski, R.; Cates, J.W. Advances in Nuclear Radiation Sensing: Enabling 3-D Gamma-Ray Vision. Sensors 2019, 19, 2541. [Google Scholar] [CrossRef] [PubMed]
  20. Sharma, M.K.; Alajo, A.B.; Lee, H.K. Three-dimensional localization of low activity gamma-ray sources in real-time scenarios. Nucl. Instrum. Methods Phys. Res. Sect. A Accel. Spectrometers Detect. Assoc. Equip. 2016, 813, 132–138. [Google Scholar] [CrossRef]
  21. Gunatilaka, A.; Ristic, B.; Gailis, R. Radiological Source Localisation. Published by DSTO Defence Science and Technology Organisation, Australia. Available online: http://www.dsto.defence.gov.au/corporate/reports/DSTO_TR_1988.pdf (accessed on 1 July 2007).
  22. Cho, H.S.; Woo, T.H. Mechanical analysis of flying robot for nuclear safety and security control by radiological monitoring. Ann. Nucl. Energy 2016, 94, 138–143. [Google Scholar] [CrossRef]
  23. Morelande, M.; Ristic, B.; Gunatilaka, A. Detection and parameter estimation of multiple radioactive sources. In Proceedings of the 10th International Conference on Information Fusion, Quebec, AB, Canada, 9–12 July 2007; pp. 1–7. [Google Scholar]
  24. Meutter, P.D.; Hoffma, I. Bayesian source reconstruction of an anomalous Selenium-75 release at a nuclear research institute. J. Environ. Radioact. 2020, 218, 1062259. [Google Scholar] [CrossRef]
  25. Pgm, A.; Sk, B.; Ntsb, E. 3D unmanned aerial vehicle radiation mapping for assessing contaminant distribution and mobility. Int. J. Appl. Earth Obs. Geoinf. 2016, 52, 12–19. [Google Scholar] [CrossRef]
  26. Kawatsuma, S.; Mimura, R.; Asama, H. Unitization for portability of emergency response surveillance robot system: Experiences and lessons learned from the deployment of the JAEA-3 emergency response robot at the Fukushima Daiichi Nuclear Power Plants. Robomech J. 2017, 4, 1. [Google Scholar] [CrossRef]
  27. Nagatani, K.; Kiribayashi, S.; Okada, Y. Emergency response to the nuclear accident at the Fukushima Daiichi Nuclear Power Plants using mobile rescue robots. J. Field Robot. 2013, 30, 44–63. [Google Scholar] [CrossRef]
  28. Ducros, C.; Hauser, G.; Mahjoubi, N. RICA: A Tracked Robot for Sampling and Radiological Characterization in the Nuclear Field. J. Field Robot. 2017, 34, 583–599. [Google Scholar] [CrossRef]
  29. Bird, B.; Griffiths, A.; Martin, H. A Robot to Monitor Nuclear Facilities: Using Autonomous Radiation-Monitoring Assistance to Reduce Risk and Cost. IEEE Robot. Autom. Mag. 2018, 26, 35–43. [Google Scholar] [CrossRef]
  30. Hou, L.; Liu, J.J.; Bai, N. Design of Surface Contamination Monitor. Nucl. Electron. Detect. Technol. 2018, 38, 485–490. [Google Scholar]
  31. Konolige, K.; Grisetti, G.; Kümmerle, R.; Burgard, W.; Limketkai, B.; Vincent, R. Efficient Sparse Pose Adjustment for 2D mapping. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems, Taipei, Taiwan, 18–22 October 2010; pp. 22–29. [Google Scholar]
  32. Kohlbrecher, S.; von Stryk, O.; Meyer, J.; Klingauf, U. A flexible and scalable slam system with full 3D motion estimation. In Proceedings of the 2011 IEEE International Symposium on Safety, Security, and Rescue Robotics (SSRR), Kyoto, Japan, 1–5 November 2011; pp. 155–160. [Google Scholar]
  33. Lu, D.V.; Hershberger, D.; Smart, W.D. Layered costmaps for context-sensitive navigation. In Proceedings of the IEEE/RSJ International Conference on Intelligent Robots & Systems, Chicago, IL, USA, 14–18 September 2014. [Google Scholar]
  34. Fallon, M.; Johannsson, H.; Kaess, M.; Leonard, J.J. The MIT stata center dataset. Int. J. Robot. Res. 2013, 32, 1695–1699. [Google Scholar] [CrossRef]
  35. Rebecq, H.; Horstschäfer, T.; Gallego, G. Evo: A geometric approach to event-based 6-dof parallel tracking and mapping in real time. IEEE Robot. Autom. Lett. 2016, 2, 593–600. [Google Scholar] [CrossRef]
  36. Wright, T.; West, A.; Licata, M. Simulating Ionising Radiation in Gazebo for Robotic Nuclear Inspection Challenges. Robotics 2021, 10, 86. [Google Scholar] [CrossRef]
Figure 1. Robotics platform.
Figure 1. Robotics platform.
Machines 10 00800 g001
Figure 2. Surface-contamination monitor’s construction diagram.
Figure 2. Surface-contamination monitor’s construction diagram.
Machines 10 00800 g002
Figure 3. Flowchart of the Cartographer algorithm.
Figure 3. Flowchart of the Cartographer algorithm.
Machines 10 00800 g003
Figure 4. Map fusion framework.
Figure 4. Map fusion framework.
Machines 10 00800 g004
Figure 5. Radiation map’s update process.
Figure 5. Radiation map’s update process.
Machines 10 00800 g005
Figure 6. Modeling results for the robotics platform, with model construction results in Gazebo on the left and model visualization results in RVIZ on the right.
Figure 6. Modeling results for the robotics platform, with model construction results in Gazebo on the left and model visualization results in RVIZ on the right.
Machines 10 00800 g006
Figure 7. The process of communicating radiation-detection data.
Figure 7. The process of communicating radiation-detection data.
Machines 10 00800 g007
Figure 8. The results of the map building on the public dataset: (a) Cartographer, (b) Gmapping, (c) Karto_SLAM, and (d) Hector_SLAM.
Figure 8. The results of the map building on the public dataset: (a) Cartographer, (b) Gmapping, (c) Karto_SLAM, and (d) Hector_SLAM.
Machines 10 00800 g008aMachines 10 00800 g008b
Figure 9. Comparison of absolute positional errors between multiple SLAM systems: (a) the graph of absolute pose errors of four SLAM methods, (b) statistic errors of four SLAM methods, and (c) box plots of four SLAM methods.
Figure 9. Comparison of absolute positional errors between multiple SLAM systems: (a) the graph of absolute pose errors of four SLAM methods, (b) statistic errors of four SLAM methods, and (c) box plots of four SLAM methods.
Machines 10 00800 g009
Figure 10. Map fusion results: (a) simulation environment, (b) grid map of the simulated environment, (c) single-radiation-source map-fusion results, and (d) multi-radiation-source map-fusion results.
Figure 10. Map fusion results: (a) simulation environment, (b) grid map of the simulated environment, (c) single-radiation-source map-fusion results, and (d) multi-radiation-source map-fusion results.
Machines 10 00800 g010
Figure 11. Real-time radiation-detection results in simulation: (a) camera view and (b) local radiation map.
Figure 11. Real-time radiation-detection results in simulation: (a) camera view and (b) local radiation map.
Machines 10 00800 g011
Figure 12. Analysis of radiation-detection data: (a) comparison of real radiation data with measured radiation data and (b) radiation-detection-data errors.
Figure 12. Analysis of radiation-detection data: (a) comparison of real radiation data with measured radiation data and (b) radiation-detection-data errors.
Machines 10 00800 g012
Figure 13. The result of the indoor scene map building: (a) the real environment, (b) the mapping result of Cartographer, (c) the mapping result of Gmapping, (d) the mapping result of Hector_SLAM, (e) the mapping result of the Karto_SLAM algorithm, and (f) the radiation mapping result of the indoor environment with one radiation source.
Figure 13. The result of the indoor scene map building: (a) the real environment, (b) the mapping result of Cartographer, (c) the mapping result of Gmapping, (d) the mapping result of Hector_SLAM, (e) the mapping result of the Karto_SLAM algorithm, and (f) the radiation mapping result of the indoor environment with one radiation source.
Machines 10 00800 g013aMachines 10 00800 g013b
Figure 14. The result of the outdoor-scene map building: (a) the real environment, (b) the mapping result of Cartographer, (c) the mapping result of Gmapping, (d) the mapping result of Hector_SLAM, (e) the mapping result of the Karto_SLAM algorithm, and (f) the radiation mapping result of the outdoor environment with multi-radiation source.
Figure 14. The result of the outdoor-scene map building: (a) the real environment, (b) the mapping result of Cartographer, (c) the mapping result of Gmapping, (d) the mapping result of Hector_SLAM, (e) the mapping result of the Karto_SLAM algorithm, and (f) the radiation mapping result of the outdoor environment with multi-radiation source.
Machines 10 00800 g014
Table 1. The abbreviations used in this paper.
Table 1. The abbreviations used in this paper.
AbbreviationsFull Name
LiDARLight detection and ranging
SLAMSimultaneous localization and mapping
IMUInertial measurement unit
LAMPScene-data fusion
SPASparse pose adjustment
BBSBranch-and-bound scan matching
TCP/IPTransmission control protocol/internet protocol
RMSERoot mean square error
TFTransform frame
ROSRobot operating system
STDStandard deviation
SSESum of squares error
APEAbsolute trajectory error
Table 2. Main parameters of the surface-contamination monitor.
Table 2. Main parameters of the surface-contamination monitor.
PerformanceParameters
Measured energy rangea > 2.5 MeV, β > 100 keV
Detection efficiencya: ≥ 25%(Am-241); β: ≥ 30%(Sr-90/Y-90)
Effective area10 × 17cm2 × 8
Operating efficiency≥3 m2/min
Table 3. Statistical summary of absolute pose error.
Table 3. Statistical summary of absolute pose error.
RMSE
(m)
MEAN
(m)
MEDIAN
(m)
STD
(m)
MIN
(m)
MAX
(m)
SSE
(m)
Cartographer0.3180460.2442960.1413100.2036500.852112739.224
Gmapping0.4788610.4449570.3968010.17697801.016416209.652
Karto_SLAM0.8160530.6367240.4275670.51043601.6546118188.1
Hector_SLAM1.339591.146671.209880.69257902.8060949009.8
Publisher’s Note: MDPI stays neutral with regard to jurisdictional claims in published maps and institutional affiliations.

Share and Cite

MDPI and ACS Style

Liu, X.; Cheng, L.; Yang, Y.; Yan, G.; Xu, X.; Zhang, Z. An Alpha/Beta Radiation Mapping Method Using Simultaneous Localization and Mapping for Nuclear Power Plants. Machines 2022, 10, 800. https://doi.org/10.3390/machines10090800

AMA Style

Liu X, Cheng L, Yang Y, Yan G, Xu X, Zhang Z. An Alpha/Beta Radiation Mapping Method Using Simultaneous Localization and Mapping for Nuclear Power Plants. Machines. 2022; 10(9):800. https://doi.org/10.3390/machines10090800

Chicago/Turabian Style

Liu, Xin, Lan Cheng, Yapeng Yang, Gaowei Yan, Xinying Xu, and Zhe Zhang. 2022. "An Alpha/Beta Radiation Mapping Method Using Simultaneous Localization and Mapping for Nuclear Power Plants" Machines 10, no. 9: 800. https://doi.org/10.3390/machines10090800

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop