Trajectory Tracking via Multiscale Continuous Attractor Networks
Abstract
Animals and insects showcase remarkably robust and adept navigational abilities, up to literally circumnavigating the globe. Primary progress in robotics inspired by these natural systems has occurred in two areas: highly theoretical computational neuroscience models, and handcrafted systems like RatSLAM and NeuroSLAM. In this research, we present work bridging the gap between the two, in the form of Multiscale Continuous Attractor Networks (MCAN), that combine the multiscale parallel spatial neural networks of the previous theoretical models with the real-world robustness of the robot-targeted systems, to enable trajectory tracking over large velocity ranges. To overcome the limitations of the reliance of previous systems on hand-tuned parameters, we present a genetic algorithm-based approach for automated tuning of these networks, substantially improving their usability. To provide challenging navigational scale ranges, we open source a flexible city-scale navigation simulator that adapts to any street network, enabling high throughput experimentation111 https://github.com/theresejoseph/Trajectory_Tracking_via_MCAN/. In extensive experiments using the city-scale navigation environment and Kitti, we show that the system is capable of stable dead reckoning over a wide range of velocities and environmental scales, where a single-scale approach fails.
I Introduction
Robotic navigation systems encounter several challenges: creating efficient maps, adapting to significant environmental changes, and long-term tracking. In contrast, biological systems have evolved efficient strategies for lifelong navigation while performing tasks such as foraging, migration, and homing. Neuroscience research on spatial representation has identified some of these mechanisms that encode and integrate sensory information to build spatial maps using models such as Continuous Attractor Networks (CAN) [1, 2, 3]. Robotics has drawn inspiration from this field and developed algorithms such as RatSLAM [4] and NeuroSLAM [5] that attempt to emulate some of the biological mechanisms of spatial navigation. These systems still face significant challenges in terms of one or more of robustness, scalability, ease of deployment, and adaptability.
In particular, robust navigation systems should be able to operate over a wide range of spatial scales without incurring excessive memory usage. While most CAN navigation systems use single-scale networks for 2D and 3D spaces, a multiscale network can switch modes of operation according to the input scale, making them suitable for long-term navigation.

This paper proposes a new multiscale biologically inspired network, with the following contributions:
-
1.
Multiscale Continuous Attractor Networks (MCAN): Our proposed Multiscale Continuous Attractor Networks (MCAN) is a bio-inspired neural network architecture with multi-scale parallel spatial neural networks building on previous theoretical models to accurately encode a wide range of velocity inputs and enable large scale trajectory tracking (Figure 1).
-
2.
A tuning method using genetic algorithms: The reliance of previous systems on hand-tuned parameters is overcome by presenting a genetic algorithm-based approach for automated tuning of the MCAN and a head direction network. This optimization method automatically identifies high performance parameter spaces in large CAN networks.
-
3.
A city-scale navigation simulator: To provide challenging navigational scale ranges, we contribute a flexible city-scale navigation simulator that adapts to any street network, enabling high throughput experimentation for evaluating path integration performance.
The paper is structured as follows: In Section II, we will provide an overview of the brain’s navigational mechanisms, attractor networks, and related research. Section III presents the methodology, which explains the process of simulating robot trajectories within city road networks, optimizing network performance using genetic algorithms, and utilizing the multiscale network architecture with attractor dynamics. The results of extensive experiments using both the new simulator and Kitti are presented in Sections IV and V, where we quantitatively compare a single-scale baseline to the proposed multiscale system. Finally, Section VI concludes the paper with recommendations for future work.
II Related Works
Section II-A introduces spatial cells in the hippocampus, including place cells, head direction cells, grid cells, and border cells, that play a critical role in mammalian navigation.Section II-B discusses the development of several computational models that integrate linear and angular velocity cues for path integration while mimicking the characteristics of spatial cells. Section II-C reviews bio-inspired robotic systems that emulate the behaviour of spatial cells within real environments using robotic hardware. Section II-D then presents methods for tuning CANs using optimization techniques, and finally, Section II-E discusses simulators for robot navigation.
II-A Navigation Mechanisms in the Brain
Mammalian navigation is a complex process that involves various spatial cells in the hippocampus, such as place cells, head direction cells, and grid cells. Place cells [6] are neurons that fire at unique spatial locations, representing places within an environment. Head direction cells [7] encode an animal’s orientation and provide information about its heading. Grid cells [8, 9, 10] use a tessellated grid pattern to integrate direction and speed, enabling efficient encoding of large environments [11]. Border cells and object vector cells are additional spatial cells that provide information about the boundaries within an environment along with the distance and direction of objects within it [12, 13]. These biological mechanisms offer an alternative to classical robotic Simultaneous Localization And Mapping (SLAM) algorithms by integrating sensory visual and motion cues to update estimates of a location while building a cognitive map of the environment.
II-B Theoretic Computational Neuroscience Models
The discovery of spatial cells led to the development of several computational models that can integrate linear and angular velocity cues for path integration while mimicking the characteristics of spatial cells. Attractor networks were proposed to model head direction [14] using neurons in a ring structure with a stable bump of activity, which shifts based on angular velocity inputs. They were also used to model grid cells with 2D CAN models that combine head direction and speed for shifting activity bumps with toroidal connections at the boundary [15, 16, 3].
Early works [17, 18, 19] implemented attractor models with unsupervised learning, while supervised models [20, 2] incorporated learning rules or error signal feedback. Other models [10, 21, 1] have used backpropagation and architecture constraints to form computational navigation models.
Although these theoretical models cannot fully replicate the complexity and nuance of how the brain solves navigational problems, they offer valuable insights into the computations that the brain employs for integration, error correction, and learning [22].
II-C Bio-inspired Robot Navigation
The discovery of navigational mechanisms in the brain also resulted in algorithms that emulate the behaviour of spatial cells in physical robotic hardware, demonstrating navigational capabilities through bio-inspiration. Early works include [23, 24, 4] which rely on place cells along with curated mechanisms like “view cells”, “transition cells” and “pose cells” based on standard robotics principles. Extensions of these works include NeuroSLAM [5] which extends RatSLAM [4] to a 3D space and [25] which corrects absolute heading using polarization of light as seen in Desert Ants.
Grid cell mechanisms have also been the basis for numerous multiscale systems in robotics such as the large-scale aerial mapping system developed by Hausler et al. [26], a grid-cell inspired place recognition system that utilizes homogeneous maps at varying scales [27], and a system for multiscale path integration in 3D for unmanned aerial vehicles (UAVs) [28]. These systems demonstrate the potential of grid cell-based models for solving complex tasks in different domains.
II-D Tuning CANs
Existing methods for tuning CANs have relied on either optimization techniques or hand-crafted network parameters to achieve stable activity that integrates input signals accurately. In early works, DeGris et al. [29] used a Genetic Algorithm to fine-tune 1D CAN networks in a spiking neuron model. Dall’Osto et al. [30] proposed an automatic calibration method utilizing global optimization methods, while Menezes et al. [31] presented an iterative closest point algorithm for automatic tuning of RatSLAM. More recently, Fox et al. [32] proposed a new evolutionary dynamic optimization method for shifting attractor peaks, along with a benchmark suite. However, with the growth of network complexity in scale and dimension, optimizing additional parameters becomes increasingly challenging.
II-E Simulators for Robot Navigation
Simulations play a crucial role in enabling rapid experimentation and development of any system. OpenStreetMap (OSM) is a crowd-sourced map that includes road network information obtained from portable GPS devices, and it has been used in several systems. For example, Brubaker et al. [33] performed self-localization using OSM maps and visual odometry. Fleischmann et al. [34] used OSM paths to assess the quality of GNSS signals during navigation. Li et al. [35] combined OSM road network paths with onboard sensors for path tracking. By integrating OSM maps with other data sources, these systems showcase the versatility and potential of OSM in various applications and motivated the simulation developed within this work.
III Methodology
Our work aims to enhance the ability of robots to navigate through large-scale environments by introducing a new multiscale extension to continuous attractor models. In Section III-A, we describe the dynamics of the 2D attractor network, which serves as the foundation of our approach. We then present the multiscale network extension in Section III-B, which enables the network to handle large-scale velocity inputs and accurately track trajectories over extended periods. Additionally, we introduce the head direction network in Section III-C, which processes the robot’s heading direction information and feeds it into the multiscale network. To further improve the usability and performance of our approach, we employ a genetic algorithm-based tuning approach, which is detailed in Section III-D. Our methodology is evaluated in a new city-scale navigation simulator that we introduce in Section III-E, providing a comprehensive evaluation of our approach’s ability to track motion through a range of large, varied street networks.
III-A Attractor Dynamics
Attractor networks are widely used in neural modelling [5] [4] [22] due to their ability to represent and maintain stable patterns of activity, even in the presence of noise and input variability. In this subsection, we describe the attractor dynamics used in our model, which is based on a 2D grid of neurons with recurrent excitatory connections. Specifically, a 2D attractor network is defined as an grid of neurons.
III-A1 Initilization
At the beginning of the simulation, the neurons in the attractor network are initialized using a 2D Gaussian function with standard deviation , which determines their initial state of activation. We initialize the activity in an region centred around neuron , resulting in the following activation profile:
(1) |
(2) |
III-A2 Network update
At the end of each time step , the activity of each neuron is divided by the L2 norm of the activity across the entire network. This ensures that the maximum magnitude of the activity vector is always one and prevents explosive activity growth:
(3) |
In this equation, the numerator represents the total input to each neuron, which is the sum of its current activity , the activity of neurons shifted into its place field based on the input velocity , the excitation caused by nearby active neurons , and the global inhibition term .
III-A3 Copying and shifting the activity packet
After initialization, the attractor network is updated by injecting the activity of active neurons back into the network with an integer offset and corresponding to the input velocity, which shifts the activity packet across the grid. To achieve this, we copy the weights of active neurons (i.e., those with an activity greater than zero) into the network, with wraparound connections at the edges. Specifically, we use the following equation:
(4) |
where is the shifted position of the active neuron , computed as .
III-A4 Fractional shifts
In addition to integer shifts, the attractor network can also handle fractional shifts, which allow the activity packet to move more smoothly across the grid. To achieve this, we use linear interpolation to modify the copied weights with a fractional offset amount and a confidence parameter , resulting in the following fractional copy function:
(5) |
III-A5 Excitation
After the activity packet has been shifted across the grid, the active neurons excite a region of size (such that represents the excitation radius), with the strength of the excitation being scaled by the weight, , of each neuron. Specifically, we use a 2D Gaussian function to compute the excitation of neuron , resulting in the following expression:
(6) |
As for the initialization, if the neuron index is outside the range and , then the activity is set to 0.
III-A6 Inhibition
To prevent the network from explosive activity growth, a global inhibition term is applied. The global inhibition that is applied to each neuron is computed by summing the activities of all neurons and scaling the result by an inhibition factor :
(7) |
This inhibition term acts as a normalizing factor, reducing all neurons’ activity when the total network activity becomes too high.
III-B Multiscale Attractor Network
The multiscale attractor network builds upon the capabilities of the single-scale attractor network by incorporating multiple 2D networks, each with its own unique scale resolution. This allows the network to capture information at various scales, which is especially relevant in spatial navigation where the agent’s velocity can span a large range. By selecting the input network with the closest spatial resolution to the agent’s speed, the network can effectively integrate motion information using attractor dynamics and enable accurate position tracking.
III-B1 Storing network wraparound
Continuous attractor networks in 2D have toroidal manifolds, i.e. the surface wraps around and reconnects with itself in the and dimension, forming a seamless and continuous space that has a torus or donut shape. This enables more efficient computation as neurons on the edge can receive input from the opposite edge. However, the toroidal manifold of the network poses a challenge in terms of preventing decoded position reset when activity wraps around an edge. By storing the distance travelled in wraparound buffers, our algorithm ensures that the agent’s position is accurately updated when the activity wraps around an edge, preventing position reset and enabling smooth navigation in the environment.
For example, if the decoded x position from the network decreases while the agent is facing right (270 < < 90), the wraparound buffer is incremented by the network size to store the magnitude of the position reset. Similarly, if the decoded x position from the network increases while the agent is facing left (90 < < 270), the wraparound buffer is decremented by the network size. In the 2D network, two wraparound buffers are used to store the distance travelled in and dimensions.
III-B2 Position decoding
The final step in the process is to decode the estimated position of the agent using the combined activity of all networks and the wraparound buffer. This is accomplished by taking the circular mean of the most active neuron’s row and column, with each network’s activity weighed by its corresponding scale resolution. The resulting position estimation is therefore a combination of the information captured at different scales, resulting in a more accurate representation of the agent’s true position. Specifically, the decoded position of networks, each of size and scale is:
(8) |
where is for decoding the position and for decoding the position, as defined previously.
III-C Head Direction Network
The head direction network plays a crucial role in the navigation system and is also modeled by a continuous attractor network, which is a well-established computational model in the field of neuroscience [7, 14]. It has a 1D ring structure, and similar to the 2D system, it uses the same tuning parameters () and attractor dynamics. At the beginning of the simulation, the 1D attractor network is initialized with a 1D Gaussian of radius . The activity in the network is updated by shifting activity packets scaled by . Excitation and inhibition are applied with radius and inhibition factor , respectively. The activity in the network is normalized after each update to maintain a stable firing rate.
The network estimates the current heading angle of the agent using the circular mean method. The circular mean is calculated by taking the weighted average of the cosine and sine of the firing angles of the neurons in the network. This method is used to ensure that the direction estimate is robust to circular data, where the values wrap around after reaching the maximum or minimum value. Overall, the head direction network provides an estimate of the agent’s heading angle, which is used in conjunction with the multiscale attractor network to update the agent’s position.
III-D Network Tuning with Genetic Algorithm
To ensure stable dynamics and accurate velocity integration, the continuous attractor network parameters activation radius , excitation radius , motion confidence , and inhibition factor must be carefully tuned. We use a genetic algorithm [36] to automate this tuning process. Genetic algorithms are a type of optimization algorithm that is commonly used to explore the fitness landscape of a set of parameters and find the optimal solution. The goal of the tuning process is to ensure that the attractor network exhibits stable dynamics and accurate velocity integration. Each parameter has an operating range that is dependent on the network size and the number of dimensions.
To explore the fitness landscape, the genetic algorithm generates an initial population of potential solutions with varying parameter values. The fitness function is evaluated for each member of the population, and the fittest individuals are selected to be the parents of the next generation. The algorithm then creates three children from the fittest parents by mutating their genes with a mutation probability. This is further detailed in Algorithm 1. Fitness is evaluated in parallel at the start of each generation to reduce computing time.
The fitness function used in this case evaluates the performance of the attractor network in integrating velocity information and providing accurate estimates of position and heading. The velocity is sampled from a uniform distribution within a desired operating range to avoid overfitting to a specific input trajectory.
Overall, the genetic algorithm provides an automated way to fine-tune the parameters of the continuous attractor network, which is essential for the system to work accurately in a variety of environments.
III-E City Scale Navigation Simulator
Our City Scale Navigation (CSN) simulator is a tool used to evaluate the performance of our proposed system in realistic scenarios. The simulator generates trajectories based on real-world road networks within a 10km 10km region from major cities. This enables the evaluation of the system’s ability to navigate through complex and dynamic urban environments. The simulator extracts road network data from Open Street Maps to generate an occupancy map consisting of traversable, realistic roads. The occupied cells in the map represent the drivable areas of the road network. A path-finding distance transform algorithm [37], is then used to find the optimal route between two randomly generated points on the road map.
Once the sample paths are generated, they can be traversed using the kinematics of a bicycle motion model [38], which is a common model used in the navigation of ground vehicles. During the traversal of the paths, motion information such as linear and angular velocities are recorded. This motion data is then used to evaluate the performance of the system, such as the accuracy of the estimated position and heading, the stability of the continuous attractor network, and the effectiveness of the buffer to prevent position resetting.
IV Experimental Setup
IV-A Implementation Details
The MCAN trajectory tracking system was implemented in Python3 using standard libraries. The head direction network consists of 360 neurons that were tuned using a genetic algorithm to accurately integrate angular velocity inputs to produce an estimate of agent orientation. The 2D networks in the multiscale system was generated with 100100 neurons and 4 scales with scale ratios incremented by a factor of 4, i.e., . This was suitable for the desired operating range of 0-20 m/s (0-72 km/h). For a fair comparison, the single-scale CAN was implemented with 200x200 neurons, so both systems had a total of 40000 neurons.
The CANs were tuned using 24 genomes mutated and evaluated for 20 generations with 14 parallel processes for fitness evaluation. Based on the network size, the parameter ranges were set to , , , and .
IV-B Datasets
The performance of our system was evaluated on the City scale navigation simulator (Section III-E) and the Kitti Odometry dataset [39], which is commonly used to benchmark robotic systems. The navigation simulator was used to generate trajectories based on road networks within a 10 km 10 km region from Tokyo, Berlin, Brisbane, and New York. These road maps were converted into occupancy grids, and a path-finding distance transform algorithm from the Robotics Toolbox for Python [37] was used to find an optimal route between two points on the road map. Our city scale simulator was used to generate paths through Tokyo, Brisbane, Berlin and New York, covering distances of 38 km, 70 km, 167 km, and 63 km, respectively. Using both the simulator and the Kitti Odometry dataset, we evaluated the proposed system in a variety of realistic scenarios.
IV-C Evaluation Metrics
Our networks were evaluated using the Absolute Trajectory Error (ATE), which is a common metric used in trajectory estimation systems [40]. ATE is defined as the Root Mean Square Error (RMSE) between the estimated and desired trajectory after alignment. In order to ensure a fair comparison between different datasets, ATE was averaged over the total distance, resulting in ATE/meter. While we used ATE to evaluate the performance of our networks, we utilized the Sum of Absolute Differences (SAD) method [41] during the tuning process to measure the fitness of the networks.
V Results and Discussion
This section provides a comparison of single-scale CAN versus the proposed multiscale system. We evaluate the performance of our system on multiple trajectories generated from simulation and existing datasets in Section V-A. This is followed by an analysis of the tuning mechanism in Section V-B.
Dataset | Single-scale | Multiscale |
---|---|---|
Tokyo (CSN simulation) | 1.093 0.110 | 0.068 0.010 |
New York (CSN simulation) | 0.893 0.137 | 0.070 0.028 |
Brisbane (CSN simulation) | 0.934 0.102 | 0.070 0.019 |
Berlin (CSN simulation) | 0.896 0.166 | 0.046 0.021 |
Kitti (odometry) | 0.136 0.138 | 0.041 0.026 |







V-A Comparison of Multiscale versus Single-Scale
Our experiments demonstrate that incorporating a multiscale system can lead to significant performance enhancements on the standard CAN model. Table I presents the average translational error (ATE) for the single-scale CAN and our proposed MCAN model on five different datasets. We observed that the ATE for MCAN was orders of magnitude lower than that of the single-scale baseline, with improvements evident across all tasks. The City Scale Navigation simulations showed the most significant difference between MCAN and CAN, likely because of their more extensive range of input velocities. On the Kitti dataset, MCAN showed performance improvements specifically in areas of the path with higher velocities and minor improvements in the other regions, as depicted in Figure 2.
Furthermore, we evaluated the impact of the input velocity range on the performance of the single-scale and multiscale systems. Figure 3 shows the ATE for different velocity ranges for the OSM simulation dataset. We can observe that the ATE of the single-scale network increases linearly with the velocity range, whereas the ATE of the MCAN increases with a smaller gradient. This demonstrates that MCAN can handle varying velocity ranges and maintain high accuracy, even when faced with challenging trajectories, generated from the tracks seen in Figure 4.
Figure 5 provides further insights into the behaviour of MCAN. It shows track segments from the Berlin CSN simulator with increasing tracking errors. Trajectories with multiple 90-degree turns have increased errors in comparison to trajectories with smaller turns.
However, these errors are orders of magnitude less than the single-scale model. An example of this is in Figure 6, where the error accumulates up to 10000 meters within the single-scale run and MCAN has a maximum error of 450 meters with less accumulation of error over time. This is further supported by Figure 7 where the MCAN error is consistently lower in all 18 tracks through Berlin.
V-B Tuning Performance
The genetic algorithm tuning procedure was successful in achieving good performance despite the added complexity of multiple interacting models. Both heading direction (1D) and multiscale (2D) tuning converged after about 3 generations, as shown in Figure 8. The multiscale tuning had limited fitness improvements after generation 2, suggesting that either there is an upper limit on what fitness is realistically possible or that the algorithm is prone to getting stuck in local optima.
VI Conclusions and Future Work
In conclusion, our proposed multiscale architecture, coupled with the genetic algorithm tuning procedure, provides a step forward in making bio-inspired systems work with both large scale simulated and real-world data and capable of handling large velocity ranges. This is a key step towards making bio-inspired networks competitive with conventional robotic navigation systems.
Through the development of a multiscale cognitive architecture, we were able to significantly enhance the performance of the continuous attractor model. Our approach results in a system capable of handling a wide range of velocities and complex environments. The proposed genetic algorithm tuning procedure allowed for efficient and effective optimization of network parameters, reducing the need for manual tuning and increasing the scalability of the system. Our results show that the genetic algorithm can successfully optimize both the heading direction and multiscale parameters, leading to improved performance in navigation tasks.
While our proposed system has shown promise, there is potential for future work to address some existing limitations. One limitation is the absence of landmarks or memorized locations of previously visited areas, which means errors could eventually accumulate without a corrective mechanism. Integrating a loop closure component will move this from a dead reckoning system to a full mapping and localization system. Although we conducted extensive simulation experiments drawing upon real world city networks as well as real-world data from Kitti, further live experimentation on deployed robot platforms will provide insights that can drive and inform future model development.
References
- [1] H Sebastian Seung “Learning continuous attractors in recurrent networks” In Advances in neural information processing systems 10, 1997
- [2] DB Arnold and DA Robinson “A learning network model of the neural integrator of the oculomotor system” In Biological cybernetics 64.6 Springer, 1991, pp. 447–454
- [3] Yoram Burak and Ila R Fiete “Accurate path integration in continuous attractor network models of grid cells” In PLoS computational biology 5.2 Public Library of Science San Francisco, USA, 2009, pp. e1000291
- [4] Michael Milford and Gordon Wyeth “Persistent navigation and mapping using a biologically inspired SLAM system” In The International Journal of Robotics Research 29.9 Sage Publications Sage UK: London, England, 2010, pp. 1131–1153
- [5] Fangwen Yu, Jianga Shang, Youjian Hu and Michael Milford “NeuroSLAM: a brain-inspired SLAM system for 3D environments” In Biological cybernetics 113, 2019, pp. 515–545
- [6] John O’Keefe “Place units in the hippocampus of the freely moving rat” In Experimental neurology 51.1 Elsevier, 1976, pp. 78–109
- [7] Jeffrey S Taube “Head direction cells and the neurophysiological basis for a sense of direction” In Progress in Neurobiology 55.3 Elsevier, 1998, pp. 225–256
- [8] Torkel Hafting et al. “Microstructure of a spatial map in the entorhinal cortex” In Nature 436.7052 Nature Publishing Group UK London, 2005, pp. 801–806
- [9] Edvard I Moser et al. “Grid cells and cortical representation” In Nature Reviews Neuroscience 15.7 Nature Publishing Group UK London, 2014, pp. 466–481
- [10] Andrea Banino et al. “Vector-based navigation using grid-like representations in artificial agents” In Nature 557.7705 Nature Publishing Group UK London, 2018, pp. 429–433
- [11] Roddy M Grieves and Kate J Jeffery “The representation of space in the brain” In Behavioural processes 135 Elsevier, 2017, pp. 113–131
- [12] Øyvind Arne Høydal et al. “Object-vector coding in the medial entorhinal cortex” In Nature 568.7752 Nature Publishing Group UK London, 2019, pp. 400–404
- [13] Trygve Solstad et al. “Representation of geometric borders in the entorhinal cortex” In Science 322.5909 American Association for the Advancement of Science, 2008, pp. 1865–1868
- [14] William Skaggs, James Knierim, Hemant Kudrimoti and Bruce McNaughton “A model of the neural basis of the rat’s sense of direction” In Advances in neural information processing systems 7, 1994
- [15] Marianne Fyhn et al. “Spatial representation in the entorhinal cortex” In Science 305.5688 American Association for the Advancement of Science, 2004, pp. 1258–1264
- [16] Bruce L McNaughton et al. “Path integration and the neural basis of the ‘cognitive map”’ In Nature Reviews Neuroscience 7.8 Nature Publishing Group UK London, 2006, pp. 663–678
- [17] Kechen Zhang “Representation of spatial orientation by the intrinsic dynamics of the head-direction cell ensemble: a theory” In Journal of Neuroscience 16.6 Soc Neuroscience, 1996, pp. 2112–2126
- [18] Alexei Samsonovich and Bruce L McNaughton “Path integration and cognitive mapping in a continuous attractor neural network model” In Journal of Neuroscience 17.15 Soc Neuroscience, 1997, pp. 5900–5920
- [19] John Widloski and Ila R Fiete “A model of grid cell development through spatial exploration and spike time-dependent plasticity” In Neuron 83.2 Elsevier, 2014, pp. 481–495
- [20] Richard Hahnloser and H Sebastian Seung “Permitted and forbidden sets in symmetric threshold-linear networks” In Advances in neural information processing systems 13, 2000
- [21] Ingmar Kanitscheider and Ila Fiete “Emergence of dynamically reconfigurable hippocampal responses by learning to perform probabilistic spatial reasoning” In bioRxiv Cold Spring Harbor Laboratory, 2017, pp. 231159
- [22] Mikail Khona and Ila R Fiete “Attractor and integrator networks in the brain” In Nature Reviews Neuroscience Nature Publishing Group UK London, 2022, pp. 1–23
- [23] Philippe Gaussier, Arnaud Revel, Jean-Paul Banquet and Vincent Babeau “From view cells and place cells to cognitive map learning: processing stages of the hippocampal system” In Biological cybernetics 86.1 Springer, 2002, pp. 15–28
- [24] Nicolas Cuperlier, Mathias Quoy and Philippe Gaussier “Neurobiologically inspired mobile robot navigation and planning” In Frontiers in neurorobotics Frontiers, 2007, pp. 3
- [25] Jinshan Li, Jinkui Chu, Ran Zhang and Kun Tong “Brain-Inspired Navigation Model Based on the Distribution of Polarized Sky-Light” In Machines 10.11 MDPI, 2022, pp. 1028
- [26] Stephen Hausler, Zetao Chen, Michael E Hasselmo and Michael Milford “Bio-inspired multi-scale fusion” In Biological cybernetics 114 Springer, 2020, pp. 209–229
- [27] Zetao Chen et al. “Bio-inspired homogeneous multi-scale place recognition” In Neural Networks 72 Elsevier, 2015, pp. 48–61
- [28] Chuang Yang et al. “A Path Integration Approach Based on Multiscale Grid Cells for Large-Scale Navigation” In IEEE Transactions on Cognitive and Developmental Systems 14.3 IEEE, 2021, pp. 1009–1020
- [29] Thomas Degris, Loıc Lacheze, Christian Boucheny and Angelo Arleo “A spiking neuron model of head-direction cells for robot orientation” In Proceedings of the International Conference on the Simulation of Adaptive Behavior, from Animals to Animats, 2004, pp. 255–263
- [30] Dominic Dall’Osto, Stephen Hausler, Adam Jacobson and Michael Milford “Automatic calibration of a biologically inspired neural network for robot SLAM” In Proceedings of the Australasian Conference on Robotics and Automation (ACRA 2018), 2018, pp. 1–10 Australian RoboticsAutomation Association (ARAA)
- [31] Matheus C Menezes et al. “Automatic tuning of RatSLAM’s parameters by Irace and iterative closest point” In IECON Annual Conference of the IEEE Industrial Electronics Society, 2020, pp. 562–568 IEEE
- [32] Matthew Fox, Shengxiang Yang and Fabio Caraffini “A new moving peaks benchmark with attractors for dynamic evolutionary algorithms” In Swarm and Evolutionary Computation 74 Elsevier, 2022, pp. 101125
- [33] Marcus A Brubaker, Andreas Geiger and Raquel Urtasun “Lost! Leveraging the crowd for probabilistic visual self-localization” In Proceedings of the IEEE Conference on Computer Vision and Pattern Recognition, 2013, pp. 3057–3064
- [34] Patrick Fleischmann, Thomas Pfister, Moritz Oswald and Karsten Berns “Using OpenStreetMap for autonomous mobile robot navigation” In Proceedings of the International Conference on Intelligent Autonomous Systems, 2017, pp. 883–895 Springer
- [35] Jing Li, Hui Qin, Junzheng Wang and Jiehao Li “OpenStreetMap-based autonomous navigation for the four wheel-legged robot via 3D-Lidar and CCD camera” In IEEE Transactions on Industrial Electronics 69.3 IEEE, 2021, pp. 2708–2717
- [36] Sourabh Katoch, Sumit Singh Chauhan and Vijay Kumar “A review on genetic algorithm: past, present, and future” In Multimedia tools and applications 80 Springer, 2021, pp. 8091–8126
- [37] Peter Corke and Jesse Haviland “Not your grandmother’s toolbox–the robotics toolbox reinvented for python” In IEEE International Conference on Robotics and Automation, 2021, pp. 11357–11363 IEEE
- [38] “KinematicBicycleModel” In GitHub repository GitHub, https://github.com/winstxnhdw/KinematicBicycleModel, 2022
- [39] Andreas Geiger, Philip Lenz and Raquel Urtasun “Are we ready for autonomous driving? The Kitti vision benchmark suite” In IEEE conference on Computer Vision and Pattern Recognition, 2012, pp. 3354–3361
- [40] Zichao Zhang and Davide Scaramuzza “A tutorial on quantitative trajectory evaluation for visual (-inertial) odometry” In IEEE/RSJ International Conference on Intelligent Robots and Systems, 2018, pp. 7244–7251 IEEE
- [41] Michael J Milford and Gordon F Wyeth “SeqSLAM: Visual route-based navigation for sunny summer days and stormy winter nights” In IEEE International Conference on Robotics and Automation, 2012, pp. 1643–1649