Active SLAM: A Review on Last Decade
Abstract
:1. Introduction
2. Introduction to Active SLAM (A-SLAM)
2.1. A-SLAM Formulation
2.2. A-SLAM Components
- Probabilistic Road Map (PRM) approaches discretize the environment representation and formulate a network graph representing the possible paths for the robot to select to reach the goal position. These approaches work in a heuristic manner and may not give the optimal path; additionally, the robot model is not incorporated in the planning phase, which may result in unexpected movements. Rapidly exploring Random Trees (RRT) [31], D* [32], and A* [33] are the widely used PRM methods. We identify these methods as geometric approaches, and in Section 2.3, we discuss the application of these methods.
- Linear Quadratic Regulator (LQR) and Model Predictive Control (MPC) formulate the robot path-planning problem as an Optimal Control Problem (OCP) and are used to compute the robot trajectory over a finite time horizon in a continuous-planning domain. Consider a robot with the state-transition equation given by , where x, u, and k are the state, control, and time, respectively. The MPC controller finds the optimal control action for a finite horizon N, as shown in Equation (12), which minimizes the relative error between the desired state and desired control effort , weighted by matrices Q and P for the penalization of state and control errors, respectively, as shown in Equation (13). The MPC is formulated as minimizing the objective function as defined in (14), which takes into account the costs related to control effort and robot state evolution over the entire prediction horizon. MPC provides an optimal trajectory incorporating the robot state model and control and state constraints, making it suitable for path planning in dynamic environments:
- Reinforcement Learning (RL) is modeled as a Markov Decision Process (MDP) where an agent at state s interacts with the environment by performing an action a and receiving a reward r. The objective is to find a good policy which maximizes the aggregation of the rewards in the long run following a value function , as shown in Equation (15), that maximizes the expected reward attained by the agent, weighted by the discount factor . In the case of visual A-SLAM, the policy may be to move the robot to more feature-rich positions to maximize the reward (observed features). Deep Reinforcement Learning (DRL) replaces the agent with a deep neural network that parameterizes the policy with some weighting parameter and is given as to maximize the future rewards of each state–action pair during the evolution of the robot trajectory. We will further discuss the application of these approaches in Section 2.4:
2.3. Geometric Approaches
2.3.1. IT-Based Approaches
- Joint entropy: The information gained at the target is evaluated by using the entropy of both the robot trajectory and map carried by each particle weighted by each trajectory’s importance weight. The best exploration target is selected, which maximizes the joint-entropy reduction and hence corresponds to higher information gain.
- Expected Map Mean: An expected mean can be defined as the mathematical expectation of the map hypotheses of a particle set. The expected map mean can be applied to detect already-traversed loops on the map. Since the computation of the gain is developing, the complexity of this method increases.
- Expected information from a policy: Kullback–Leibler divergence [36] is used to drive an upper bound on the divergence between the true posterior and the approximated pose belief. Apart from the information consistency of the particle filter, this method also considers the information loss due to inconsistent mapping.
2.3.2. Frontier-Based Exploration
2.3.3. Path-Planning Optimization
2.3.4. Optimization in Robot Trajectory
2.3.5. Optimal Policy Selection
2.4. Dynamic Approaches
2.5. Hybrid Approaches
2.6. Reasoning over Spectral Graph Connectivity
2.7. Statistical Analysis on A-SLAM
3. Active Collaborative SLAM (AC-SLAM)
3.1. Network Topology of AC-SLAM
3.2. Collaborative Localization
3.3. Exploration and Exploitation Tasks
3.4. Trajectory Planning
3.5. Statistical Analysis on AC-SLAM
4. Discussion and Future Directions
4.1. General Limitations
- Stopping criteria: Since A-SLAM is computationally expensive especially when the utility function is computed over the entire mapped area (e.g., map entropy) or in the case of TOED, the mapping of the full information matrix is required. The quantification of uncertainties from TOED may be used as an interesting stopping criterion, as discussed by [19]. The interesting approach proposed by [106] shows the qualification of uncertainty, e.g., D-optimality and the amount of explored area to stop autonomous exploration and mapping.
- Robust data associations: Contrary to SLAM where an internal controller is responsible for robot action and the data association (the association between measurements and corresponding landmarks) has less impact on robot actions, in A-SLAM, a robust data association guides the controller to select feature-rich positions. The qualification of these good feature/landmark positions may be difficult, especially beyond line-of-sight measurements.
- Dynamic environments: In A-SLAM, the nature of the environment (static or dynamic) and the characteristics of obstacles (static or dynamic) significantly influence the utility function used to plan future actions. While the majority of the A-SLAM literature primarily addresses static environments and obstacles, this focus may not align well with the complexities of real-world scenarios marked by dynamic elements. This article advocates for a broader exploration of A-SLAM in dynamic contexts, highlighting the need for adaptable and responsive robotic systems capable of thriving in real-world conditions.
- Simulation environment: When considering DRL-based approaches, the model training is constrained to a simulated environment, and contrary to Deep Learning approaches, an offline dataset cannot be used. The trained model may not perform optimally in real-world scenarios with high uncertainty.
4.2. Limitations of Existing Methods
- Limited consideration of dynamic obstacles: As mentioned earlier in Section 2.2, A-SLAM involves decision and planning in unknown environments. These environments may have dynamic obstacles, as in real-world scenarios. In such a case, the SLAM algorithm must be able to detect dynamic obstacles and recompute its utility and path. In [41], the authors employed a novel approach that leverages D* [32] with negative edge weights for adaptive path planning in the presence of dynamic obstacles. Keeping into consideration the robot localization uncertainty, this method takes into account the obstacle Euclidean distance and updates the D* planner weights. The approach in [9] detects dynamic obstacles in a crowded environment, and the utility function takes into account the change in Shannon’s entropy [59] upon the detection of dynamic obstacles.
- High computational complexity: A-SLAM is computationally expensive, as mentioned in Section 2.1 and Section 2.2. We find only a few approaches that tackle this issue. The authors of [38] present a scenario with multiple prior topometric subgraphs, and a novel approach is introduced. It alternates between active localization and mapping and uses maximum likelihood estimation to streamline the method’s computational complexity. In an interesting approach using the methods in Section 2.3, the authors of [34] tackle the joint-entropy minimization exploration problem by introducing two versions of RRT* [31], which use distance and entropy change per distance traveled in the utility function, hence lowering the computational complexity. In AC-SLAM, the authors of [94] introduce a novel method for strengthening weak connections in the target robot’s pose graphs by the host robot. Weak connections are identified when the covariance surpasses a predefined threshold and is resolved through communication, addressing the 1-ESP problem [63]. The methods explained in Section 2.6 provide a good basis for the development of less computationally expensive A-SLAM algorithms.
- Real robot deployment: A-SLAM is necessary for real robot deployment because it enables robots to make decisions about where and how to select informative goal positions, adapt to changing environments, and operate effectively and autonomously in complex and dynamic environments. From the results of Section 2.7 and Section 3.5, we recall that real robots are used only in 67% and 37% of A-SLAM and AC-SLAM methods, respectively.
- Limited implementation of loop closure: Loop closure [107] is important in SLAM to ensure map consistency and integrity, minimize localization errors and drift, assist with global map alignment, and optimize map accuracy. It is essential for the reliable and accurate mapping and localization required in various robotic applications. In Section 2.7 and Section 3.5, we recall that loop closure is implemented in only 51% and 62.5% of A-SLAM and AC-SLAM methods, respectively. This limited use is justified by the fact that it involves the heavy computation of minimizing the localization error and exploitation (revisiting already-traversed areas of the environment), which may not be suitable for A-SLAM, which is already computationally expensive (Section 2.1 and Section 2.2).
- Reasoning over graph connectivity: As mentioned in Section 2.6, new methods are available to reduce the A-SLAM computational complexity, whereby debates over the SLAM pose-graph connectivity metrics and new methods for uncertainty quantification have occurred. The authors of [66] treat the underlying graph as an estimation-over-graph (EoG) [62] SLAM problem and propose a new method of computing the D-optimality criterion over the reduced weighted graph Laplacian matrix. In an AC-SLAM approach, the method presented in [94] also exploits the graph connectivity to find weak edges in the target robot pose graph and guides the host robot to localize it.
- Limited ROS implementation: ROS [22] is an open-source framework for robotics research. It provides a collection of libraries for sensor integration, perception, navigation, control, visualization, and analysis for many robotics platforms [108]. From Section 2.7 and Section 3.5, we can infer that ROS usage has been limited to only 45% and 31.2% of articles on A-SLAM and AC-SLAM, respectively. This limited ROS usage is related to the increased computational overhead on the A-SLAM algorithm, which decreases the real-time and performance requirements.
- Less usage of dynamic approaches: As discussed in Section 2.4, these approaches treat path planning in A-SLAM as an Optimal Control Problem and work on continuous planning and action spaces. They have the advantage of incorporating the robot kinematic and dynamic models into the cost function, resulting in a smooth trajectory [109] with dynamic obstacle detection. Our analysis in Section 2.7 signifies that only 11% of A-SLAM methods use this approach, mainly due to the associated computational overhead.
- Lack of usage of heterogeneous robots: Utilizing heterogeneous robots in AC-SLAM can enhance the mapping accuracy, improve the system robustness, increase coverage, enable multiperspective mapping, and support efficient exploration by leveraging complementary sensor modalities and capabilities among the robots. Section 2.7 shows that 66.6% of approaches use UGV and UAV collaboration for collaborative mapping [89,93,95] and information gathering [101].
- Managing robust communication: Robust communication implies the ability of a network to function smoothly when one or many robots/servers fail. In the case of A-SLAM, it is deduced to be a system that is immune to failure when any agent loses localization or gets out of the communication range. Most of the AC-SLAM approaches in Section 3 fail to address this issue. An interesting approach by the authors of [96] proposes a rendezvous method to manage the limited communication bandwidth by relocating robots to predefined positions when they move beyond the communication range.
- Communication bandwidth management: Communication bandwidth management is vital in AC-SLAM for ensuring real-time collaboration, minimizing latency, conserving resources, and optimizing cost efficiency. From the analysis in Section 3, we can infer that no AC-SLAM implementation addresses communication bandwidth management. The approach presented in [110] proposes many different visual and visual–inertial information-sharing schemes for SLAM and loop closure, which are bandwidth friendly and can be applied in AC-SLAM.
4.3. Future Prospects
- Detection and avoidance of dynamic obstacles: Dynamic obstacle detection and avoidance are crucial for autonomous robot navigation in unfamiliar or partially known environments. The effective management of both static and dynamic obstacle avoidance directly impacts uncertainty propagation and system entropy. In [111], the authors introduce a perception-aware Next-Best Viewpoint Planner (NBVP) [112] designed for dynamic obstacles incorporating active-loop closure. This planner employs a keypoint filtration and selection method based on the yaw angle, the number of previously detected keypoints, and the UAV’s distance to choose optimal loop-closure keypoints. Additionally, in a computationally efficient approach by [113], the authors combine multiple obstacle detectors and utilize a Kalman filter for efficient dynamic obstacle detection and tracking. For Lidar measurements, [114] proposes a method involving dynamic object segmentation and classification based on kd-nearest neighborhood search [115].
- Lowering computational complexity for real-time applications: As discussed earlier, the utility criterion in TOED and relative entropy computation are both computationally extensive tasks, thus limiting the real-time performance of A-SLAM. Machine learning approaches like CNNs can be used to reduce the computational overhead of loop closure in SLAM, as proposed by the authors of [116]. Leveraging the advantages of edge-cloud computing [117], the robot pose and local/global map can be estimated by utilizing the edge-cloud processing capabilities, as used by the authors of [118].
- Application of DRL methods: As mentioned in Section 2.4, DRL methods have the capacity to handle complex decision-making processes in continuous states and action spaces. They enable adaptive exploration–exploitation trade-offs, making them well suited for the challenges encountered in real-world A-SLAM scenarios. Deep Q networks (DQN) and double dueling (D3QN) are applications of such DRL approaches used by [13,55]. A memory-efficient solution as compared to traditional DRL approaches is presented by the authors of [119] where the robot already has a partial map of the environment inside the external memory and uses a neural-network-based navigation strategy for autonomous exploration. The method in [120] presents an interesting DRL A-SLAM method that improves exploration by incorporating the robot pose uncertainty in the reward function to favor loop closure.
- Advanced simulators: The use of advanced simulators is crucial for A-SLAM due to their realistic modeling, cost efficiency, and support for diverse scenarios. Commercially available simulators like AirSim [121], Carla [122], and Webots [123] provide realistic modeling of urban environments for UGV, UAV, and cars. For multirobots, MvSim [124], and for SLAM, the Virtual Reality (VR)-supported simulator proposed in [125], can be used.
- Multisensor fusion: Multisensor fusion enhances perception, adaptability, obstacle detection, reliability, loop closure, tracking, and localization in real-world A-SLAM. Sensor fusion is a very mature topic, and interested readers are directed to [126,127] for review articles. When using Deep Learning (DL) approaches is concerned, the authors of [128] present an actor–critic self-adopting agent for the weighing-sensors (camera, Lidar, IMU, GPS) SLAM method. An interesting method for fusing light and Lidar measurements to map and localize agents by using an Extended Kalman Filter (EKF) is presented by the authors of [129].
- Graph connectivity metrics: As explained in Section 2.6, a novel approach for assessing A-SLAM uncertainty is presented. This approach involves quantifying the reliability of SLAM through measures such as algebraic, degree, and tree connectivity within the pose graph. It is noteworthy that this method, as demonstrated in [64,65,66], provides a computationally efficient alternative to A-SLAM.
- Advance embedded design: Advanced embedded design methods are essential for real-time processing, low latency, sensor integration, robustness, real-world testing, and the overall optimized performance of A-SLAM. Referring to Table 3 and Table 6, we can infer that most approaches use commercially available robots with limited embedded processing capabilities. The authors of [130] propose an efficient Field Programmable Gate Arrays (FPGA)-based vision system for obstacle detection in real time at 30 Frames Per Second (FPS). To improve the computational capabilities for navigation tasks, the authors of [131] propose a method to add an external embedded board to the Khepra IV [132] robot.
- Internet of Things (IoT) and cloud computing: IoT and cloud computing offer scalable data processing, remote access, data fusion, and machine learning capabilities. The approach adopted by the authors of [133] proposes a Deep Learning (DL) model incorporated with cloud computing and IoT technologies and works with wearable glucose-level-monitoring equipment for the efficient future prediction of blood glucose levels.
5. Conclusions
Author Contributions
Funding
Institutional Review Board Statement
Informed Consent Statement
Data Availability Statement
Acknowledgments
Conflicts of Interest
References
- Dhiman, N.K.; Deodhare, D.; Khemani, D. Where Am I? Creating Spatial Awareness in Unmanned Ground Robots Using SLAM: A Survey. Sadhana 2015, 40, 1385–1433. [Google Scholar] [CrossRef]
- Saeedi, S.; Paull, L.; Trentini, M.; Li, H. Multiple Robot Simultaneous Localization and Mapping. In Proceedings of the 2011 IEEE/RSJ International Conference on Intelligent Robots and System, San Francisco, CA, USA, 25–30 September 2011; pp. 853–858. [Google Scholar]
- Grisetti, G.; Kummerle, R.; Stachniss, C.; Burgard, W. A Tutorial on Graph-Based SLAM. IEEE Intell. Transp. Syst. Mag. 2010, 2, 31–43. [Google Scholar] [CrossRef]
- Pancham, A.; Tlale, N.; Bright, G. Literature review of SLAM and DATMO. In Proceedings of the 4th Robotics and Mechatronics Conference of South Africa (RobMech 2011), CSIR International Conference Centre, Pretoria, South Africa, 23–25 November 2011. [Google Scholar]
- Zamora, E.; Yu, W. Recent Advances on Simultaneous Localization and Mapping for Mobile Robots. IETE Tech. Rev. 2013, 30, 490. [Google Scholar] [CrossRef]
- Nabil, M.; Kassem, M.H.; Bahnasy, A.; Shehata, O.M.; Morgan, E.-S.I. Rescue missions bots using A-SLAM and map feature extraction. In Proceedings of the 4th International Conference on Control, Mechatronics and Automation–ICCMA ’16, Barcelona, Spain, 7–11 December 2016. [Google Scholar] [CrossRef]
- Li, G.; Geng, Y.; Zhang, W. Autonomous Planetary Rover Navigation via A-SLAM. Aircr. Eng. Aerosp. Technol. 2018, 91, 60–68. [Google Scholar] [CrossRef]
- Chen, Y.; Huang, S.; Fitch, R. A-SLAM for mobile robots with area coverage and obstacle avoidance. IEEE/ASME Trans. Mechatronics 2020, 25, 1182–1192. [Google Scholar] [CrossRef]
- Mammolo, D. A-SLAM in Crowded Environments. Master’s Thesis, Autonomous Systems Lab, ETH Zurich, Zurich, Switzerland, 2019. [Google Scholar] [CrossRef]
- Chaves, S.M.; Eustice, R.M. Efficient planning with the Bayes Tree for A-SLAM. In Proceedings of the 2016 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Daejeon, Republic of Korea, 9–14 October 2016. [Google Scholar] [CrossRef]
- Palomeras, N.; Carreras, M.; Andrade-Cetto, J. A-SLAM for autonomous underwater exploration. Remote Sens. 2019, 11, 2827. [Google Scholar] [CrossRef]
- Suresh, S.; Sodhi, P.; Mangelson, J.G.; Wettergreen, D.; Kaess, M. A-SLAM using 3D SUBMAP saliency for underwater volumetric exploration. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2020. [Google Scholar] [CrossRef]
- Wen, S.; Zhao, Y.; Yuan, X.; Wang, Z.; Zhang, D.; Manfredi, L. Path planning for A-SLAM based on deep reinforcement learning under unknown environments. Intell. Serv. Robot. 2020, 13, 263–272. [Google Scholar] [CrossRef]
- Perdigão, J.D.S. Collaborative-Control Based Navigation of Mobile Human-Centered Robots. Master’s Thesis, University of Coimbra, Coimbra, Portugal, 2014. Available online: http://hdl.handle.net/10316/40415 (accessed on 20 February 2022).
- Arvanitakis, I.; Tzes, A. Collaborative mapping and navigation for a mobile robot swarm. In Proceedings of the 2017 25th Mediterranean Conference on Control and Automation (MED), Valletta, Malta, 3–6 July 2017. [Google Scholar]
- Leung, C.; Huang, S.; Dissanayake, G. A-SLAM using model predictive control and attractor based exploration. In Proceedings of the IEEE/RSJ International Conference of Intelligent Robots Systems, Beijing, China, 9–13 October 2006; pp. 5026–5031. [Google Scholar]
- Feder, H.J.S. Simultaneous Stochastic Mapping and Localization. Ph.D. Thesis, Dept. Mech. Eng., MIT, Cambridge, MA, USA, 1999. [Google Scholar]
- Barto, A.G.; Sutton, R.S. Goal Seeking Components for Adaptive Intelligence: An Initial Assessment; Air Force Wright Aeronautical Laboratories: Dayton, OH, USA, 1981. [Google Scholar]
- Cadena, C.; Carlone, L.; Carrillo, H.; Latif, Y.; Scaramuzza, D.; Neira, J.; Reid, I.; Leonard, J.J. Past, Present, and Future of Simultaneous Localization and Mapping: Toward the Robust-Perception Age. IEEE Trans. Robot. 2016, 32, 1309–1332. [Google Scholar] [CrossRef]
- Lluvia, I.; Lazkano, E.; Ansuategi, A. Active Mapping and Robot Exploration: A Survey. Sensors 2021, 21, 2445. [Google Scholar] [CrossRef]
- Placed, J.A.; Strader, J.; Carrillo, H.; Atanasov, N.; Indelman, V.; Carlone, L.; Castellanos, J.A. A survey on active simultaneous localization and mapping: State of the art and new frontiers. IEEE Trans. Robot. 2023, 39, 1686–1705. [Google Scholar] [CrossRef]
- Morgan, Q.; Ken, C.; Brian, G.; Josh, F.; Tully, F.; Jeremy, L.; Rob, W.; Andrew, N. ROS: An Open-Source Robot Operating System; ICRA Workshop on Open Source Software: Kobe, Japan, 2009; Volume 3, No. 3.2; p. 5. [Google Scholar]
- Gratton, S.; Lawless, A.S.; Nichols, N.K. Approximate Gauss–Newton Methods for Nonlinear Least Squares Problems. SIAM J. Optim. 2007, 18, 106–132. [Google Scholar] [CrossRef]
- Watson, G.A. Lecture Notes in Mathematics. In Proceedings of the 7th Dundee Biennial Conference on Numerical Analysis, Dundee, UK, 28 June–1 July 1977; Springer: Berlin/Heidelberg, Germany, 1978. ISBN 978-3-540-08538-6. [Google Scholar]
- Fox, D.; Burgard, W.; Thrun, S. Active Markov Localization for Mobile Robots. Robot. Auton. Syst. 1998, 25, 195–207. [Google Scholar] [CrossRef]
- Placed, J.A.; Castellanos, J.A. A Deep Reinforcement Learning Approach for Active SLAM. Appl. Sci. 2020, 10, 8386. [Google Scholar] [CrossRef]
- Yamauchi, B. A frontier-based approach for autonomous exploration. In Proceedings of the 1997 IEEE International Symposium on Computational Intelligence in Robotics and Automation CIRA’97, ‘Towards New Computational Principles for Robotics and Automation’, Monterey, CA, USA, 10–11 July 1997; pp. 146–151. [Google Scholar] [CrossRef]
- Available online: https://github.com/aws-robotics/aws-robomaker-small-house-world (accessed on 10 January 2023).
- Pázman, A. Foundations of Optimum Experimantal Design; Springer: Berlin/Heidelberg, Germany, 1996; Volume 14. [Google Scholar]
- Stachniss, C.; Grisetti, G.; Burgard, W. Information Gain-Based Exploration Using Rao-Blackwellized Particle Filters. In Proceedings of the Robotics: Science and Systems I, Massachusetts Institute of Technology, Cambridge, MA, USA, 8 June 2005; pp. 65–72. [Google Scholar] [CrossRef]
- Naderi, K.; Rajamäki, J.; Hämäläinen, P. RT-RRT*: A real-time path planning algorithm based on RRT*. In Proceedings of the 8th ACM SIGGRAPH Conference on Motion in Games, Paris, France, 16–18 November 2015; pp. 113–118. [Google Scholar]
- Stentz, A. The D* Algorithm for Real-Time Planning of Optimal Traverses; Technical Report; CMU-RI-TR-94-37; Robotics Institute, Carnegie Mellon University: Pittsburgh, PA, USA, 1994. [Google Scholar]
- Liu, X.; Gong, D. A comparative study of A-star algorithms for search and rescue in perfect maze. In Proceedings of the 2011 International Conference on Electric Information and Control Engineering, Wuhan, China, 15–17 April 2011. [Google Scholar]
- Vallve, J.; Andrade-Cetto, J. Active pose slam with RRT. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015. [Google Scholar] [CrossRef]
- Du, J.; Carlone, L.; Kaouk, N.M.; Bona, B.; Indri, M. A comparative study on A-SLAM and autonomous exploration with particle filters. In Proceedings of the 2011 IEEE/ASME International Conference on Advanced Intelligent Mechatronics (AIM), Budapest, Hungary, 3–7 July 2011; pp. 916–923. [Google Scholar] [CrossRef]
- Carlone, L.; Du, J.; Kaouk, N.M.; Bona, B.; Indri, M. A-SLAM and exploration with particle filters using Kullback-Leibler divergence. J. Intell. Robot. Syst. 2013, 75, 291–311. [Google Scholar] [CrossRef]
- Mu, B.; Giamou, M.; Paull, L.; Agha-Mohammadi, A.; Leonard, J.; How, J. Information-based A-SLAM via topological feature graphs. In Proceedings of the 2016 IEEE 55th Conference on Decision and Control (CDC), Las Vegas, NV, USA, 12–14 December 2016. [Google Scholar] [CrossRef]
- Xue, W.; Ying, R.; Wen, F.; Chen, Y.; Liu, P. A-SLAM with prior topo-metric graph starting at uncertain position. IEEE Robot. Autom. Lett. 2022, 7, 1134–1141. [Google Scholar] [CrossRef]
- Trivun, D.; Salaka, E.; Osmankovic, D.; Velagic, J.; Osmic, N. A-SLAM-based algorithm for autonomous exploration with Mobile Robot. In Proceedings of the 2015 IEEE International Conference on Industrial Technology (ICIT), Seville, Spain, 17–19 March 2015. [Google Scholar] [CrossRef]
- Kaess, M.; Ranganathan, A.; Dellaert, F. ISAM: Incremental Smoothing and Mapping. IEEE Trans. Robot. 2008, 24, 1365–1378. [Google Scholar] [CrossRef]
- Maurovic, I.; Seder, M.; Lenac, K.; Petrovic, I. Path Planning for Active SLAM Based on the D* Algorithm with Negative Edge Weights. IEEE Trans. Syst. Man Cybern Syst. 2018, 48, 1321–1331. [Google Scholar] [CrossRef]
- Hsiao, M.; Mangelson, J.G.; Suresh, S.; Debrunner, C.; Kaess, M. ARAS: Ambiguity-aware robust A-SLAM based on multi-hypothesis state and map estimations. In Proceedings of the 2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Las Vegas, NV, USA, 24 October 2020–24 January 2021. [Google Scholar] [CrossRef]
- Lenac, K.; Kitanov, A.; Maurović, I.; Dakulović, M.; Petrović, I. Fast Active SLAM for Accurate and Complete Coverage Mapping of Unknown Environments. In Intelligent Autonomous Systems 13; Menegatti, E., Michael, N., Berns, K., Yamaguchi, H., Eds.; Advances in Intelligent Systems and Computing; Springer International Publishing: Cham, Switzerland, 2016; Volume 302, pp. 415–428. ISBN 978-3-319-08337-7. [Google Scholar]
- Ekman, A.; Torne, A.; Stromberg, D. Exploration of polygonal environments using range data. IEEE Trans. Syst. Man, Cybern. Part B 1997, 27, 250–255. [Google Scholar] [CrossRef]
- Eustice, R.M.; Singh, H.; Leonard, J.J. Exactly Sparse Delayed-State Filters for View-Based SLAM. IEEE Trans. Robot. 2006, 22, 1100–1114. [Google Scholar] [CrossRef]
- Soragna, A.; Baldini, M.; Joho, D.; Kummerle, R.; Grisetti, G. A-SLAM using connectivity graphs as Priors. In Proceedings of the 2019 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Macau, China, 3–8 November 2019. [Google Scholar] [CrossRef]
- Sökmen, Ö.; Emeç, Ş.; Yilmaz, M.; Akkaya, G. An Overview of Chinese Postman Problem. In Proceedings of the 3rd International Conference on Advanced Engineering Technologies, Turkey, 19–20 September 2019. [Google Scholar]
- He, Y.; Liang, B.; Yang, J.; Li, S.; He, J. An iterative closest points algorithm for registration of 3D laser scanner point clouds with geometric features. Sensors 2017, 17, 1862. [Google Scholar] [CrossRef]
- Carrillo, H.; Reid, I.; Castellanos, J.A. On the comparison of uncertainty criteria for A-SLAM. In Proceedings of the 2012 IEEE International Conference on Robotics and Automation, Saint Paul, MN, USA, 14–18 May 2012. [Google Scholar] [CrossRef]
- Rodriguez-Arevalo, M.L.; Neira, J.; Castellanos, J.A. On the importance of uncertainty representation in A-SLAM. IEEE Trans. Robot. 2018, 34, 829–834. [Google Scholar] [CrossRef]
- Carrillo, H.; Latif, Y.; Rodriguez-Arevalo, M.L.; Neira, J.; Castellanos, J.A. On the Monotonicity of optimality criteria during exploration in A-SLAM. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015. [Google Scholar] [CrossRef]
- Bemporad, A. Model predictive control design: New trends and tools. In Proceedings of the 45th IEEE Conference on Decision and Control, San Diego, CA, USA, 13–15 December 2006; pp. 6678–6683. [Google Scholar] [CrossRef]
- Jayaweera, S.K. Markov decision processes. In Signal Processing for Cognitive Radios; Wiley: Hoboken, NJ, USA, 2015; pp. 207–268. [Google Scholar] [CrossRef]
- Qiang, W.; Zhongli, Z. Reinforcement learning model, algorithms and its application. In Proceedings of the 2011 International Conference on Mechatronic Science, Electric Engineering and Computer (MEC), Jilin, China, 19–22 August 2011; pp. 1143–1146. [Google Scholar] [CrossRef]
- Martinez-Marin, T.; Lopez, E.; De Bernardis, C. An unified framework for A-SLAM and Online Optimal Motion Planning. In Proceedings of the 2011 IEEE Intelligent Vehicles Symposium (IV), Baden-Baden, Germany, 5–9 June 2011. [Google Scholar] [CrossRef]
- Andrade, F.; LLofriu, M.; Tanco, M.M.; Barnech, G.T.; Tejera, G. Active localization for mobile service robots in symmetrical and Open Environments. In Proceedings of the 2021 Latin American Robotics Symposium (LARS), 2021 Brazilian Symposium on Robotics (SBR), and 2021 Workshop on Robotics in Education (WRE), Natal, Brazil, 11–15 October 2021. [Google Scholar] [CrossRef]
- Liu, Y.; Zhu, D.; Peng, J.; Wang, X.; Wang, L.; Chen, L.; Li, J.; Zhang, X. Robust active visual slam system based on Bionic Eyes. In Proceedings of the 2019 IEEE International Conference on Cyborg and Bionic Systems (CBS), Munich, Germany, 18–20 September 2019. [Google Scholar] [CrossRef]
- Bonetto, E.; Goldschmid, P.; Pabst, M.; Black, M.J.; Ahmad, A. iRotate: Active visual slam for Omnidirectional Robots. Robot. Auton. Syst. 2022, 154, 104102. [Google Scholar] [CrossRef]
- Shannon, C.E. A mathematical theory of communication. Bell Syst. Tech. J. 1948, 27, 623–656. [Google Scholar] [CrossRef]
- Findeisen, R.; Allgöwer, F. An introduction to nonlinear model predictive control. In Proceedings of the 21st Benelux Meeting on Systems and Control, Veldhoven, The Netherlands, 19–21 March 2002. [Google Scholar]
- Chen, Y.; Huang, S.; Fitch, R.; Yu, J. Efficient A-SLAM based on submap joining, graph topology and convex optimization. In Proceedings of the 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, QLD, Australia, 21–25 May 2018. [Google Scholar] [CrossRef]
- Khosoussi, K.; Sukhatme, G.S.; Huang, S.; Dissanayake, G. Maximizing the Weighted Number of Spanning Trees: Near-t-Optimal Graphs. arXiv 2016, arXiv:1604.01116. [Google Scholar]
- Khosoussi, K.; Giamou, M.; Sukhatme, G.S.; Huang, S.; Dissanayake, G.; How, J.P. Reliable Graphs for SLAM. Int. J. Robot. Res. 2019, 38, 260–298. [Google Scholar] [CrossRef]
- Placed, J.A.; Castellanos, J.A. A General Relationship Between Optimality Criteria and Connectivity Indices for Active Graph-SLAM. IEEE Robot. Autom. Lett. 2023, 8, 816–823. [Google Scholar] [CrossRef]
- Placed, J.A.; Rodríguez, J.J.G.; Tardós, J.D.; Castellanos, J.A. ExplORB-SLAM: Active Visual SLAM Exploiting the Pose-graph Topology. In Proceedings of the Fifth Iberian Robotics Conference. ROBOT 2022. Lecture Notes in Networks and Systems; Springer: Cham, Switzerland, 2023; Volume 589. [Google Scholar]
- Placed, J.A.; Castellanos, J.A. Fast Autonomous Robotic Exploration Using the Underlying Graph Structure. In Proceedings of the 2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Prague, Czech Republic, 27 September 2021; pp. 6672–6679. [Google Scholar]
- Deray, J.; Solà, J. Manif: A micro Lie theory library for state estimation in robotics applications. J. Open Source Softw. 2020, 5, 1371. [Google Scholar] [CrossRef]
- Kummerle, R.; Grisetti, G.; Strasdat, H.; Konolige, K.; Burgard, W. G2o: A General Framework for Graph Optimization. In Proceedings of the 2011 IEEE International Conference on Robotics and Automation, Shanghai, China, 9–13 May 2011; pp. 3607–3613. [Google Scholar]
- Blanco-Claraco, J.-L.; Leanza, A.; Reina, G. A General Framework for Modeling and Dynamic Simulation of Multibody Systems Using Factor Graphs. Nonlinear Dyn. 2021, 105, 2031–2053. [Google Scholar] [CrossRef]
- Rösmann, C.; Feiten, W.; Wösch, T.; Hoffmann, F.; Bertram, T. Trajectory Modification Considering Dynamic Constraints of Autonomous Robots. In Proceedings of the ROBOTIK 2012 7th German Conference on Robotics, Munich, Germany, 21–22 May 2012. [Google Scholar]
- Fox, D.; Burgard, W.; Thrun, S. The Dynamic Window Approach to Collision Avoidance. IEEE Robot. Autom. Mag. 1997, 4, 23–33. [Google Scholar] [CrossRef]
- Kim, P.; Chen, J.; Kim, J.; Cho, Y.K. SLAM-Driven Intelligent Autonomous Mobile Robot Navigation for Construction Applications. In Advanced Computing Strategies for Engineering; Smith, I.F.C., Domer, B., Eds.; Lecture Notes in Computer Science; Springer International Publishing: Cham, Switzerland, 2018; Volume 10863, pp. 254–269. ISBN 978-3-319-91634-7. [Google Scholar]
- Kalogeiton, V.S.; Ioannidis, K.; Sirakoulis, G.C.; Kosmatopoulos, E.B. Real-time A-SLAM and obstacle avoidance for an autonomous robot based on Stereo Vision. Cybern. Syst. 2019, 50, 239–260. [Google Scholar] [CrossRef]
- Pang, L.; Hu, J.; Xiao, P.; Liu, S. A-SLAM based on geometry rules and forward simulation in Exploration Space. In Proceedings of the 2018 IEEE International Conference on Information and Automation (ICIA), Wuyishan, China, 11–13 August 2018. [Google Scholar] [CrossRef]
- An, S.-Y.; Lee, L.-K.; Oh, S.-Y. Ceiling vision-based A-SLAM framework for dynamic and wide-open environments. Auton. Robot. 2015, 40, 291–324. [Google Scholar] [CrossRef]
- Deng, X.; Zhang, Z.; Sintov, A.; Huang, J.; Bretl, T. Feature-constrained active visual slam for Mobile Robot Navigation. In Proceedings of the 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, QLD, Australia, 21–25 May 2018. [Google Scholar] [CrossRef]
- Zhang, L.; Zhang, Z.; Siegwart, R.; Chung, J.J. Optimized motion strategy for active target localization of mobile robots with time-varying connectivity: Extended abstract. In Proceedings of the 2019 International Symposium on Multi-Robot and Multi-Agent Systems (MRS), New Brunswick, NJ, USA, 22–23 August 2019. [Google Scholar] [CrossRef]
- Yang, Z.X.; Jin, S. UAV A-SLAM trajectory programming based on optimal control. Adv. Mater. Res. 2013, 765–767, 1932–1935. [Google Scholar] [CrossRef]
- Lourenco, P.; Batista, P.; Oliveira, P.; Silvestre, C. Torwards uncertainty optimization in A-SLAM. In Proceedings of the 2015 54th IEEE Conference on Decision and Control (CDC), Osaka, Japan, 15–18 December 2015. [Google Scholar] [CrossRef]
- Wu, Y.; Zhang, Y.; Zhu, D.; Chen, X.; Coleman, S.; Sun, W.; Hu, X.; Deng, Z. Object SLAM-based active mapping and robotic grasping. In Proceedings of the 2021 International Conference on 3D Vision (3DV), London, UK, 1–3 December 2021. [Google Scholar] [CrossRef]
- Botteghi, N.; Alaa, K.; Sirmacek, B.; Poel, M. Entropy-Based Exploration for Mobile Robot Navigation: A Learning-Based Approach. In Proceedings of the Planning and Robotics Workshop, Nancy, France, 14–15 June 2020. [Google Scholar]
- Huang, J.; Zhou, B.; Fan, Z.; Zhu, Y.; Jie, Y.; Li, L.; Cheng, H. FAEL: Fast Autonomous Exploration for Large-Scale Environments With a Mobile Robot. IEEE Robot. Autom. Lett. 2023, 8, 1667–1674. [Google Scholar] [CrossRef]
- Mihálik, M.; Malobický, B.; Peniak, P.; Vestenický, P. The New Method of Active SLAM for Mapping Using LiDAR. Electronics 2022, 11, 1082. [Google Scholar] [CrossRef]
- Yuwen, X.; Zhang, H.; Yan, F.; Chen, L. The Gaze Control of the Active Visual SLAM with A Novel Panoramic Cost Map. IEEE Trans. Intell. Veh. 2022, 8, 1813–1825. [Google Scholar] [CrossRef]
- Xu, M.; Song, Y.; Chen, Y.; Huang, S.; Hao, Q. Invariant EKF based 2D A-SLAM with Exploration Task. In Proceedings of the 2021 IEEE International Conference on Robotics and Automation (ICRA), Xi’an, China, 30 May–5 June 2021. [Google Scholar] [CrossRef]
- Indelman, V. Towards cooperative multi-robot belief space planning in unknown environments. Robot. Res. 2018, l, 441–457. [Google Scholar] [CrossRef]
- Indelman, V. Towards multi-robot active collaborative state estimation via belief space planning. In Proceedings of the 2015 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Hamburg, Germany, 28 September–2 October 2015. [Google Scholar] [CrossRef]
- Pham, V.C.; Juang, J.C. An Improved Active SLAM Algorithm for Multi-robot Exploration. In Proceedings of the SICE Annual Conference, Tokyo, Japan, 13–18 September 2011; pp. 1660–1665. [Google Scholar]
- Meng, Z.; Sun, H.; Qin, H.; Chen, Z.; Zhou, C.; Ang, M.H. Intelligent robotic system for autonomous exploration and active slam in unknown environments. In Proceedings of the 2017 IEEE/SICE International Symposium on System Integration (SII), Taipei, Taiwan, 11–14 December 2017. [Google Scholar] [CrossRef]
- Ossenkopf, M.; Castro, G.; Pessacg, F.; Geihs, K.; De Cristoforis, P. Long-Horizon Active Slam system for multi-agent coordinated exploration. In Proceedings of the 2019 European Conference on Mobile Robots (ECMR), Prague, Czech Republic, 4–6 September 2019. [Google Scholar] [CrossRef]
- Kontitsis, M.; Theodorou, E.A.; Todorov, E. Multi-robot active slam with relative entropy optimization. In Proceedings of the 2013 American Control Conference, Washington, DC, USA, 17–19 June 2013. [Google Scholar] [CrossRef]
- Pei, Z.; Piao, S.; Quan, M.; Qadir, M.Z.; Li, G. Active collaboration in relative observation for multi-agent visual simultaneous localization and mapping based on Deep Q Network. Int. J. Adv. Robot. Syst. 2020, 17, 172988142092021. [Google Scholar] [CrossRef]
- Qin, H.; Meng, Z.; Meng, W.; Chen, X.; Sun, H.; Lin, F.; Ang, M.H. Autonomous exploration and mapping system using heterogeneous UAVs and UGVs in GPS-denied environments. IEEE Trans. Veh. Technol. 2019, 68, 1339–1350. [Google Scholar] [CrossRef]
- Chen, Y.; Zhao, L.; Lee, K.M.; Yoo, C.; Huang, S.; Fitch, R. Broadcast your weaknesses: Cooperative active pose-graph slam for multiple robots. IEEE Robot. Autom. Lett. 2020, 5, 2200–2207. [Google Scholar] [CrossRef]
- Li, J.; Cheng, Y.; Zhou, J.; Chen, J.; Liu, Z.; Hu, S.; Leung, V.C. Energy-efficient ground traversability mapping based on UAV-UGV collaborative system. IEEE Trans. Green Commun. Netw. 2022, 6, 69–78. [Google Scholar] [CrossRef]
- Pham, V.C.; Juang, J.C. A multi-robot, cooperative, and active SLAM algorithm for exploration. Int. J. Innov. Comput. Inf. Control 2013, 9, 2567–2583. [Google Scholar]
- Pei, Z.; Piao, S.; Souidi, M.; Qadir, M.; Li, G. Slam for humanoid multi-robot active cooperation based on relative observation. Sustainability 2018, 10, 2946. [Google Scholar] [CrossRef]
- Batinović, A.; Oršulić, J.; Petrović, T.; Bogdan, S. Decentralized Strategy for Cooperative Multi-Robot Exploration and Mapping. IFAC-PapersOnLine 2020, 53, 9682–9687. [Google Scholar] [CrossRef]
- Jadhav, N.; Behari, M.; Wood, R.; Gil, S. Multi-Robot Exploration without Explicit Information Exchange; Technical Report; Harvard University: Cambridge, MA, USA, 2022. [Google Scholar]
- Atanasov, N.; Le Ny, J.; Daniilidis, K.; Pappas, G.J. Decentralized Active Information Acquisition: Theory and Application to Multi-Robot SLAM. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015; pp. 4775–4782. [Google Scholar]
- Schlotfeldt, B.; Thakur, D.; Atanasov, N.; Kumar, V.; Pappas, G.J. Anytime Planning for Decentralized Multirobot Active Information Gathering. IEEE Robot. Autom. Lett. 2018, 3, 1025–1032. [Google Scholar] [CrossRef]
- Dubois, R.; Eudes, A.; Frémont, V. Sharing visual-inertial data for collaborative decentralized simultaneous localization and mapping. Robot. Auton. Syst. 2022, 148, 103933. [Google Scholar] [CrossRef]
- Mur-Artal, R.; Tardos, J.D. ORB-SLAM2: An Open-source SLAM system for monocular, stereo, and RGB-D cameras. IEEE Trans. Robot. 2017, 33, 1255–1262. [Google Scholar] [CrossRef]
- Takleh Omar Takleh, T.; Abu Bakar, N.; Abdul Rahman, S.; Hamzah, R.; Abd Aziz, Z. A Brief Survey on SLAM Methods in Autonomous Vehicle. IJET 2018, 7, 38. [Google Scholar] [CrossRef]
- Gammell, J.D.; Srinivasa, S.S.; Barfoot, T.D. Batch Informed Trees (BIT*): Sampling-Based Optimal Planning via the Heuristically Guided Search of Implicit Random Geometric Graphs. In Proceedings of the 2015 IEEE International Conference on Robotics and Automation (ICRA), Seattle, WA, USA, 26–30 May 2015; pp. 3067–3074. [Google Scholar]
- Placed, J.A.; Castellanos, J.A. Enough Is Enough: Towards Autonomous Uncertainty-Driven Stopping Criteria. IFAC-PapersOnLine 2022, 55, 126–132. [Google Scholar] [CrossRef]
- Newman, P.; Ho, K. SLAM-Loop Closing with Visually Salient Features. In Proceedings of the 2005 IEEE International Conference on Robotics and Automation, Barcelona, Spain, 18–22 April 2005; pp. 635–642. [Google Scholar] [CrossRef]
- Cooney, M.; Yang, C.; Siva, A.P.; Arunesh, S.; David, J. Teaching Robotics with Robot Operating System (ROS): A Behavior Model Perspective. In Proceedings of the Workshop on “Teaching Robotics with ROS”, European Robotics Forum 2018, Tampere, Finland, 13–15 March 2018. [Google Scholar]
- Kon, K.; Fukushima, H.; Matsuno, F. Trajectory Generation Based on Model Predictive Control with Obstacle Avoidance between Prediction Time Steps. IFAC Proc. Vol. 2009, 42, 529–535. [Google Scholar] [CrossRef]
- Dubois, R.; Eudes, A.; Frémont, V. On Data Sharing Strategy for Decentralized Collaborative Visual-Inertial Simultaneous Localization And Mapping. In Proceedings of the 2019 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Macau, China, 3–8 November 2019; pp. 2123–2130. [Google Scholar] [CrossRef]
- Zhao, Y.; Xiong, Z.; Zhou, S.; Wang, J.; Zhang, L.; Campoy, P. Perception-Aware Planning for Active SLAM in Dynamic Environments. Remote Sens. 2022, 14, 2584. [Google Scholar] [CrossRef]
- Bircher, A.; Kamel, M.; Alexis, K.; Oleynikova, H.; Siegwart, R. Receding Horizon “Next-Best-View” Planner for 3D Exploration. In Proceedings of the 2016 IEEE International Conference on Robotics and Automation (ICRA), Stockholm, Sweden, 16–21 May 2016; pp. 1462–1468. [Google Scholar]
- Xu, Z.; Zhan, X.; Xiu, Y.; Suzuki, C.; Shimada, K. Low Computational-Cost Detection and Tracking of Dynamic Obstacles for Mobile Robots with RGB-D Cameras. arXiv 2023, arXiv:2303.00132. [Google Scholar]
- Dekan, M.; František, D.; Andrej, B.; Jozef, R.; Dávid, R.; Josip, M. Moving Obstacles Detection Based on Laser Range Finder Measurements. Int. J. Adv. Robot. Syst. 2018, 15, 172988141774813. [Google Scholar] [CrossRef]
- Borelli, R.; Dovier, A.; Fogolari, F. Data Structures and Algorithms for k-th Nearest Neighbours Conformational Entropy Estimation. Biophysica 2022, 2, 340–352. [Google Scholar] [CrossRef]
- Zhou, D.; Luo, Y.; Zhang, Q.; Xu, Y.; Chen, D.; Zhang, X. A Lightweight Neural Network for Loop Closure Detection in Indoor Visual SLAM. Int. J. Comput. Intell. Syst. 2023, 16, 49. [Google Scholar] [CrossRef]
- Pal, S.; Jhanjhi, N.Z.; Abdulbaqi, A.S.; Akila, D.; Almazroi, A.A.; Alsubaei, F.S. A Hybrid Edge-Cloud System for Networking Service Components Optimization Using the Internet of Things. Electronics 2023, 12, 649. [Google Scholar] [CrossRef]
- Lv, T.; Zhang, J.; Chen, Y. A SLAM Algorithm Based on Edge-Cloud Collaborative Computing. J. Sens. 2022, 2022, 7213044. [Google Scholar] [CrossRef]
- Zhang, J.; Tai, L.; Liu, M.; Boedecker, J.; Burgard, W. Neural SLAM: Learning to Explore with External Memory. arXiv 2017, arXiv:1706.09520. [Google Scholar]
- Alcalde, M.; Ferreira, M.; Gonzalez, P.; Andrade, F.; Tejera, G. DA-SLAM: Deep Active SLAM Based on Deep Reinforcement Learning. In Proceedings of the 2022 Latin American Robotics Symposium (LARS), 2022 Brazilian Symposium on Robotics (SBR), and 2022 Workshop on Robotics in Education (WRE), São Bernardo do Campo, Brazil, 18 October 2022; pp. 282–287. [Google Scholar]
- Shah, S.; Dey, D.; Lovett, C.; Kapoor, A. AirSim: High-Fidelity Visual and Physical Simulation for Autonomous Vehicles. In Proceedings of the Field and Service Robotics: Results of the 11th International Conference; Springer: Cham, Switzerland, 2018. [Google Scholar] [CrossRef]
- Alan, D.; German, R.; Felipe, C.; Antonio, L. CARLA: An Open Urban Driving Simulator. In Proceedings of the 1st Annual Conference on Robot Learning, Mountain View, CA, USA, 13–15 November 2017; pp. 1–16. [Google Scholar]
- Starý, V.; Gacho, L. Webots open source robot simulator capabilities for modelling and simulation of ground-based air defence. In Proceedings of the 2022 20th International Conference on Mechatronics - Mechatronika (ME), Pilsen, Czech Republic, 7–9 December 2022; pp. 1–5. [Google Scholar] [CrossRef]
- Blanco-Claraco, J.-L.; Tymchenko, B.; Mañas-Alvarez, F.J.; Cañadas-Aránega, F.; López-Gázquez, Á.; Moreno, J.C. MultiVehicle Simulator (MVSim): Lightweight Dynamics Simulator for Multiagents and Mobile Robotics Research. SoftwareX 2023, 23, 101443. [Google Scholar] [CrossRef]
- Bettens, A.M.; Morrell, B.; Coen, M.; McHenry, N.; Wu, X.; Gibbens, P.; Chamitoff, G. UnrealNavigation: Simulation Software for Testing SLAM in Virtual Reality. In Proceedings of the AIAA Scitech 2020 Forum, Orlando, FL, USA, 6 January 2020. [Google Scholar]
- Xu, X.; Zhang, L.; Yang, J.; Cao, C.; Wang, W.; Ran, Y.; Tan, Z.; Luo, M. A Review of Multi-Sensor Fusion SLAM Systems Based on 3D LIDAR. Remote Sens. 2022, 14, 2835. [Google Scholar] [CrossRef]
- Chen, W.; Zhou, C.; Shang, G.; Wang, X.; Li, Z.; Xu, C.; Hu, K. SLAM Overview: From Single Sensor to Heterogeneous Fusion. Remote Sens. 2022, 14, 6033. [Google Scholar] [CrossRef]
- Jia, Y.; Luo, H.; Zhao, F.; Jiang, G.; Li, Y.; Yan, J.; Jiang, Z.; Wang, Z. Lvio-Fusion: A Self-Adaptive Multi-Sensor Fusion SLAM Framework Using Actor-Critic Method. In Proceedings of the 2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Prague, Czech Republic, 27 September 2021; pp. 286–293. [Google Scholar]
- Guan, W.; Huang, L.; Wen, S.; Yan, Z.; Liang, W.; Yang, C.; Liu, Z. Robot Localization and Navigation Using Visible Light Positioning and SLAM Fusion. J. Light. Technol. 2021, 39, 7040–7051. [Google Scholar] [CrossRef]
- Benabid, S.; Latour, L.; Poulain, S.; Jaafar, M. FPGA-Based Real-Time Embedded Vision System for Autonomous Mobile Robots. In Proceedings of the 2019 IEEE 62nd International Midwest Symposium on Circuits and Systems (MWSCAS), Dallas, TX, USA, 4–7 August 2019; pp. 1093–1096. [Google Scholar]
- Marroquín, A.; Garcia, G.; Fabregas, E.; Aranda-Escolástico, E.; Farias, G. Mobile Robot Navigation Based on Embedded Computer Vision. Mathematics 2023, 11, 2561. [Google Scholar] [CrossRef]
- Farias, G.; Fabregas, E.; Torres, E.; Bricas, G.; Dormido-Canto, S.; Dormido, S. A Distributed Vision-Based Navigation System for Khepera IV Mobile Robots. Sensors 2020, 20, 5409. [Google Scholar] [CrossRef] [PubMed]
- Nasser, A.R.; Hasan, A.M.; Humaidi, A.J.; Alkhayyat, A.; Alzubaidi, L.; Fadhel, M.A.; Santamaría, J.; Duan, Y. IoT and Cloud Computing in Health-Care: A New Wearable Device and Cloud-Based Deep Learning Algorithm for Monitoring of Diabetes. Electronics 2021, 10, 2719. [Google Scholar] [CrossRef]
Topics | [19] | [20] | [21] | Ours |
---|---|---|---|---|
Problem formulation | ✗ | ✗ | ✓ | ✓ |
Entropy, TOED | Briefly | Briefly | ✓ | ✓ |
DRL, MPC, LQR | Briefly | ✗ | ✓ | ✓ |
Single-robot analysis | Briefly | ✓ | ✓ | ✓ |
Single-robot stat. analysis | ✗ | Briefly | Briefly | ✓ |
Multirobot methods | ✗ | ✗ | Briefly | ✓ |
Multirobot stat. analysis | ✗ | ✗ | ✗ | ✓ |
Limitations | Briefly | Briefly | ✓ | ✓ |
Future perspectives | ✗ | ✗ | ✓ | ✓ |
Article | Year | Sensors | SLAM Method | Path Planning |
---|---|---|---|---|
[7] | 2017 | Lidar | EKF SLAM | Active revisit path planning |
[43] | 2016 | RGBD 1, Lidar 2, IMU 3, WE 14 | ES-DSF (EKF based) 15 | A* |
[72] | 2018 | Lidar, RGB | Hector SLAM | Artificial potential fields |
[58] | 2022 | Lidar 4, RGBD 5 | Graph based | NMPC 16, A* |
[73] | 2019 | RGB | Graph based | CAO 20 |
[6] | 2016 | Lidar, RGB | EKF-SLAM | Maze solver algorithm |
[35] | 2011 | Lidar | Particle filter | Joint entropy, EMMI 17 |
[56] | 2021 | Lidar | ACML | - |
[34] | 2015 | Lidar | Graph SLAM | RRT* |
[39] | 2015 | Lidar 6 | FastSLAM | A*, DWA 18 |
[74] | 2018 | Lidar | Gmapping | Sequential Monte Carlo |
[8] | 2020 | RGB | EKF based | MPC |
[46] | 2019 | Lidar | Graph SLAM | CPP 19 |
[75] | 2016 | Lidar, RGB | IEKF SLAM | Dijkstra, VSICP 21 |
[55] | 2011 | Lidar 7, RGB | Metric-based scan-matching SLAM | Reinforcement Learning |
[42] | 2020 | Lidar, RGBD, IMU | Graph SLAM (iSAM2) | Straight line search for each hypothesis |
[36] | 2014 | Lidar | Particle filter | Frontier-based exploration |
[61] | 2018 | ORS 27 | EKF SLAM | MPC |
[10] | 2016 | RGB | Graph SLAM (GTSAM) | Bayes tree, RRT* |
[76] | 2018 | RGBD 8 | ORB-SLAM2 | RRT* |
[37] | 2016 | RGB | TFG SLAM | Probabilistic Road Map |
[9] | 2019 | Lidar | Canonical scan matcher + iSAM2 | Dijkstra, DOO 22 |
[49] | 2012 | RBS 28 | EKF-SLAM | A* |
[77] | 2019 | - | EKF localization | A* |
[41] | 2018 | Lidar 2D 9, 3D 10 | Graph SLAM-based ESDSF 23 | Modified D* |
[11] | 2019 | MBS 29 | Graph SLAM | RRT* |
[78] | 2013 | RGB | EKF SLAM | OCBN 24 |
[79] | 2015 | Lidar, IMU | Sensor-based SLAM | - |
[13] | 2020 | RGBD, Lidar 11 | FastSLAM | DRL 25 |
[12] | 2020 | RGB, IMU | Graph SLAM | RRT |
[38] | 2022 | RGB | ORB-SLAM | RPP 26 |
[80] | 2021 | Lidar, IMU | RIEKF SLAM-based A-SLAM | - |
[80] | 2021 | RGB | Object SLAM | - |
[57] | 2019 | RGBD 1 | ORBSLAM 2 | TEB local planner |
[65] | 2022 | Lidar | Gmapping | Deep Q learning |
[26] | 2020 | RGBD 12,13, IMU | Graph SLAM | - |
[64] | 2023 | Lidar | OpenKarto (g2o) | DWA 18 |
[81] | 2020 | Lidar | Gmapping | DDPG 30 |
[82] | 2023 | Lidar | Graph SLAM | A* |
[66] | 2021 | Lidar | Open Karto (g2o) | Dijkstra |
[83] | 2022 | Lidar 31 | EKF SLAM | A* |
[84] | 2022 | RGBD 5, IMU | ORBSLAM 3, VINS Fusion | - |
Articles | Robots | Drive Type | Dataset | Loop Closure | ROS | Map Type | Utility Function |
---|---|---|---|---|---|---|---|
[72] | CD 6 | SS 1 | - | - | ✓ | OG 7 and PC 8 | FD 9 |
[58] | Robotino | OD 3 | - | ✓ | ✓ | OG | Entropy |
[73] | Survyer SVS | TD 4 | - | - | - | OG and PC | Visual features |
[6] | Khepra | DD 2 | - | - | - | OG | Image corners |
[35] | - | - | ACES, Intel Research Labs, Friburg 079 | - | - | OG | Entropy |
[56] | TurtleBot 2 | DD | - | - | ✓ | OG | Particle clustering |
[34] | - | - | Friburg 079 | ✓ | - | OG | Entropy |
[39] | Pioneer 3-DX | DD | - | - | ✓ | OG | FD |
[46] | - | DD | MIT CSAIL, Intel Research Lab, AutoLab ROS | - | - | TM 10 | D-optimality |
[75] | Pioneer DX3 | DD | - | - | - | TM | Entropy |
[42] | - | - | - | ✓ | - | TM | FD |
[36] | - | - | ACES, Intel Research Labs, Friburg 079 | ✓ | - | OG | KLD |
[61] | - | - | - | ✓ | - | TM | D-optimality |
[76] | Jackal Robot | SS | - | ✓ | ✓ | OG | FD |
[37] | TurtleBot | DD | - | - | ✓ | TM | Entropy |
[9] | Pioneer 3-DX, Pepper | DD, Humanoid type | - | ✓ | ✓ | OG | D-optimality |
[49] | - | - | DLR Dataset | - | - | TM | D-optimality |
[41] | Clearpath Huskey | DD | - | ✓ | ✓ | TM | Distance based |
[11] | Girona 500 | AUV 5 | - | - | - | TM | Entropy |
[13] | TurtleBot 3 | DD | - | - | - | OG | Exploration |
[38] | - | - | - | ✓ | - | TM | Distance |
[85] | - | - | - | ✓ | - | TM | Distance |
[80] | - | - | - | ✓ | - | Segmented | Entropy |
[57] | CD | SS | - | ✓ | - | PC | ORB Features |
[65] | TurtleBot 3 | DD | - | ✓ | ✓ | OG | D-optimality |
[26] | TurtleBot 3 | DD | - | - | ✓ | OG | Entropy |
[64] | TurtleBot 3 | DD | Friburg 079, CSAIL, FRH, MIT, INTEL | ✓ | ✓ | TM | D-optimality |
[81] | Husarion ROSbot | SS | - | - | ✓ | TM | Entropy |
[82] | JackalRobot, custom designed | SS, DD | - | ✓ | ✓ | 3D OG | FD |
[66] | TurtleBot | DD | FRH | ✓ | ✓ | OG | D-optimality |
[83] | Omnidirectional robot | OD | - | - | - | OG | Distance based |
Articles | Network Topology | Collaboration Parameters |
---|---|---|
[86] | ✤ 1 | Multirobot belief evolution by incorporating mutual observations and future measurements |
[92] | ◆ 2 | Relative observation between agents |
[88] | ◆ | Localization utility, information gain, cost of navigation |
[93] | ◆ | Visual features, map points |
[94] | ✤ | Weak edges in pose graphs of target agents |
[95] | ✤ | Frontier points and map information |
[96] | ◆ | Localization utility, information gain, cost of navigation |
[89] | ◆ | Visual features, optimized paths |
[90] | ◆ | Pose and map entropy, Kullback–Leibler divergence |
[91] | ✤ | Relative pose entropy |
[97] | ✤ | Visual features, chained localization |
[87] | ✤ | Multirobot belief evolution by incorporating mutual observations and future measurements |
[98] | ◆ | Frontier points and frontier-to-robot distances |
[99] | ◆ | Frontiers and relative-position estimates |
[100] | ◆, ✤ | Entropy and future measurements |
[101] | ◆, ✤ | Information vector and information matrix |
Papers | Years | Sensors | SLAM Method | Path Planning | Utility Function |
---|---|---|---|---|---|
[86] | 2018 | Lidar, RGB | Pose-graph SLAM | Probabilistic Road Map | Evolution of uncertainty |
[92] | 2020 | RGBD 1, IMU | ORB-SLAM2 | - | Subgraph info. and distance |
[88] | 2011 | Lidar, IMU | EKF-SLAM | A* | FI 3, distance, evolution of uncertainty |
[93] | 2019 | Lidar, RGBD 1, magnetic compass, IMU | Vision-based SLAM | FSOTP 2, BIT*-H [105] | FI |
[94] | 2020 | RGB, IMU | Pose-graph SLAM | RRT | Pose-graph connectivity |
[95] | 2015 | Lidar, RGB | Visual SLAM | - | Conditional entropy |
[96] | 2013 | Lidar, RGB | EKF-SLAM | Frontier based | FI, distance, evolution of uncertainty |
[89] | 2017 | Lidar, RGBD 1, RGB, IMU | Vision and Lidar SLAM | FSOTP 2, BIT*-H | FI, distance |
[90] | 2019 | Lidar, IMU | Graph SLAM | - | Entropy |
[91] | 2013 | Lidar, IMU | EKF SLAM | - | Relative entropy |
[97] | 2018 | RGB | ORBSLAM2 | D* | Localization uncertainty |
[87] | 2015 | Lidar, IMU | Graph SLAM | RRT* | Localization uncertainty |
[98] | 2020 | Lidar | Google Cartographer | - | FI, distance |
[99] | 2022 | UWB, WiFi | Graph SLAM | - | FI, mutual distance |
[100] | 2015 | Lidar | Information filter | - | Entropy, MI |
[101] | 2018 | Lidar | EKF | - | Entropy |
Papers | Analytical Results | Sim. Results | Real Robots | Env. | MR 2 | Robot Types | Loop Closure | ROS |
---|---|---|---|---|---|---|---|---|
[86] | ✓ | ✓ | ✗ | Two | - | ✓ | - | |
[92] | ✓ | ✓ | ✗ | Four | - | ✓ | ✓ | |
[88] | ✓ | ✓ | ✗ | Two | - | - | - | |
[93] | ✓ | ✓ | ✓ | Two | UAV, UGV (custom made) | ✓ | ✓ | |
[94] | ✓ | ✓ | ✓ | Two | UAV (custom made) | ✓ | - | |
[95] | ✓ | ✓ | ✓ | Two | UAV, UGV | - | - | |
[96] | ✓ | ✓ | ✗ | ✓ | - | - | - | |
[89] | ✓ | ✓ | ✓ | Two | UAV, UGV | ✓ | - | |
[90] | ✓ | ✓ | ✗ | ✓ | - | - | - | |
[91] | ✓ | ✓ | ✗ | ✓ | - | ✓ | - | |
[97] | ✓ | ✓ | ✗ | ✓ | - | ✓ | ✓ | |
[87] | ✓ | ✓ | ✗ | ✓ | - | ✓ | - | |
[98] | ✓ | ✓ | ✗ | Five | - | ✓ | ✓ | |
[99] | ✓ | ✓ | ✓ | Two | UGV (TurtleBot 3) | ✓ | ✓ | |
[100] | ✓ | ✓ | ✗ | ✓ | - | - | - | |
[101] | ✓ | ✓ | ✓ | Five | UGV, UAV | - | - |
Disclaimer/Publisher’s Note: The statements, opinions and data contained in all publications are solely those of the individual author(s) and contributor(s) and not of MDPI and/or the editor(s). MDPI and/or the editor(s) disclaim responsibility for any injury to people or property resulting from any ideas, methods, instructions or products referred to in the content. |
© 2023 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/).
Share and Cite
Ahmed, M.F.; Masood, K.; Fremont, V.; Fantoni, I. Active SLAM: A Review on Last Decade. Sensors 2023, 23, 8097. https://doi.org/10.3390/s23198097
Ahmed MF, Masood K, Fremont V, Fantoni I. Active SLAM: A Review on Last Decade. Sensors. 2023; 23(19):8097. https://doi.org/10.3390/s23198097
Chicago/Turabian StyleAhmed, Muhammad Farhan, Khayyam Masood, Vincent Fremont, and Isabelle Fantoni. 2023. "Active SLAM: A Review on Last Decade" Sensors 23, no. 19: 8097. https://doi.org/10.3390/s23198097
APA StyleAhmed, M. F., Masood, K., Fremont, V., & Fantoni, I. (2023). Active SLAM: A Review on Last Decade. Sensors, 23(19), 8097. https://doi.org/10.3390/s23198097