Next Article in Journal
Hybrid Algorithms Based on Two Evolutionary Computations for Image Classification
Previous Article in Journal
Adaptive Differentiated Parrot Optimization: A Multi-Strategy Enhanced Algorithm for Global Optimization with Wind Power Forecasting Applications
Previous Article in Special Issue
Multi-AUV Dynamic Cooperative Path Planning with Hybrid Particle Swarm and Dynamic Window Algorithm in Three-Dimensional Terrain and Ocean Current Environment
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Article

Migratory Bird-Inspired Adaptive Kalman Filtering for Robust Navigation of Autonomous Agricultural Planters in Unstructured Terrains

Key Laboratory of Bionic Engineering, Ministry of Education, Jilin University, Changchun 130022, China
*
Author to whom correspondence should be addressed.
Biomimetics 2025, 10(8), 543; https://doi.org/10.3390/biomimetics10080543
Submission received: 9 July 2025 / Revised: 8 August 2025 / Accepted: 17 August 2025 / Published: 19 August 2025
(This article belongs to the Special Issue Computer-Aided Biomimetics: 3rd Edition)

Abstract

This paper presents a bionic extended Kalman filter (EKF) state estimation algorithm for agricultural planters, inspired by the bionic mechanism of migratory birds navigating in complex environments, where migratory birds achieve precise localization behaviors by fusing multi-sensory information (e.g., geomagnetic field, visual landmarks, and somatosensory balance). The algorithm mimics the migratory bird’s ability to integrate multimodal information by fusing laser SLAM, inertial measurement unit (IMU), and GPS data to estimate the position, velocity, and attitude of the planter in real time. Adopting a nonlinear processing approach, the EKF effectively handles nonlinear dynamic characteristics in complex terrain, similar to the adaptive response of a biological nervous system to environmental perturbations. The algorithm demonstrates bio-inspired robustness through the derivation of the nonlinear dynamic teaching model and measurement model and is able to provide high-precision state estimation in complex environments such as mountainous or hilly terrain. Simulation results show that the algorithm significantly improves the navigation accuracy of the planter in unstructured environments. A new method of bio-inspired adaptive state estimation is provided.

1. Introduction

Technological advances in autonomous navigation of agricultural machinery are critical to address labor shortages, increase efficiency, and reduce environmental impact [1,2]. Large self-propelled plant protection machines (Figure 1) play a key role in crop management by reducing waste and environmental pollution through precise application of pesticides and fertilizers [3]. However, precise navigation of these machines in complex agricultural environments faces significant challenges due to changing terrain, obstacles, and dynamic conditions [4,5].
Traditional navigation systems usually rely on Global Navigation Satellite Systems (GNSSs) such as GPS, but signal multipath effects, occlusion, and interference in agricultural environments may affect their performance [6,7]. To overcome these limitations, sensor fusion techniques combine sensors such as GPS, inertial measurement unit (IMU), and laser SLAM to significantly improve navigation accuracy [8,9]. Among them, extended Kalman filtering (EKF) is a powerful tool for integrating multi-source sensor data to estimate machine states with high accuracy.
In recent years, bionics has provided new inspirations in the field of robotics and navigation [10,11], developing innovative robotic systems that mimic natural organisms and enhance performance in various environments. For example, Giovanni Bianch et al. designed snake-inspired aquatic robots that demonstrate better maneuverability in waters [12]. Similarly, Xiaolong He et al. designed quadrupedal robots based on a SLIP model of running animals to achieve efficient and stable mobility on land [13]. In addition, the field of biomimetic optimization has also developed the Migratory Birds Optimization (MBO) algorithm. This algorithm simulates the flight patterns used by migratory birds to solve complex optimization problems. Proposed by Duman et al. in 2012, MBO operates by arranging solutions in a V-shape, where the leader solution explores new neighborhoods, and follower solutions benefit from shared improvements, reducing computational redundancy [14]. Key advantages of MBO include its efficiency in balancing exploration and exploitation, lower sensitivity to initial parameters compared to traditional metaheuristics, and superior performance in discrete optimization tasks due to its neighborhood-sharing mechanism, which emulates birds’ energy conservation during migration [14,15]. Recent achievements highlight MBO’s versatility. For instance, in 2024, an enhanced MBO hybridized with simulated annealing achieved state-of-the-art results in global optimization benchmarks, outperforming standard genetic algorithms by up to 15% in convergence speed [15]; another 2024 study applied an improved MBO to closed-loop supply chain network design, reducing costs by 12% over particle swarm optimization (PSO) in real-world logistics scenarios [16]. Compared to other algorithms like PSO or ant colony optimization (ACO), MBO excels in problems with high-dimensional search spaces, as it requires fewer iterations (e.g., 20–30% less than PSO in quadratic assignment problems) and avoids premature convergence through dynamic benefit-sharing [14,17]. In the context of navigation and filtering, MBO has been explored for parameter tuning in Kalman filters, such as optimizing noise covariances in UAV systems inspired by bird migration senses [18]. This is consistent with the biomimetic EKF proposed in this article.
Migratory birds exhibit remarkable navigational abilities during migration, being able to travel across thousands of kilometers to reach their destinations with precision. This ability stems from their integration of multimodal sensory information from visual landmarks (e.g., mountains, rivers), geomagnetic fields, and somatosensory balance (e.g., acceleration and angular velocity perceived by the vestibular system) [19,20]. For example, under clear weather, migratory birds mainly rely on visual landmarks for localization; however, in cloudy or stormy weather, they dynamically adjust their strategies by increasing their reliance on geomagnetic fields or somatosensory sensations to adapt to environmental perturbations [21]. In this study, based on the above neuronavigation characteristics of migratory birds, a bionic extended Kalman filter (EKF) algorithm is proposed, with the following mapping relationship.
Sensory confidence is mapped from the frequency of discharge or the intensity of response of migratory birds’ sensory neurons to external stimuli. For example, when the visual information is clear, the activity of the relevant neurons of migratory birds is enhanced, corresponding to a higher confidence level; however, in low visibility environments, such as windy and rainy conditions, the neural discharge of this channel is weakened, corresponding to a decrease in the confidence level [22,23].
The sensitivity coefficients correspond to the slopes or gains of the different sensory systems of migratory birds in response to signal changes, i.e., the degree of sensitivity of neurons to input stimuli. For example, the vestibular system of migratory birds responds faster than the geomagnetic system during vigorous maneuvers and has a higher sensitivity coefficient [24,25]. Thus, the sensitivity coefficients reflect the response properties inherent in the physiological structure of the sensory channels in migratory birds [26].
Dynamic process noise regulation coefficients model the adjustment of migratory birds’ tolerance to predictive mechanisms when external signals become weak or ambiguous, corresponding to the regulation of uncertainty in the feedforward and feedback pathways in the migratory bird’s nervous system with respect to intrinsic state prediction mechanisms [27]. Such regulation is reflected in the enhanced tolerance and weighting of the neural system’s own motion model when it does not perceive the outside adequately [28].
Time-varying measurement noise tuning, on the other hand, maps from the ability to learn and adapt to short-term learning of sensory channels in the nervous system. Examples include neuromodulatory behavior under repeated stimuli in migratory birds [27].
Although a variety of organisms possess navigation capabilities (e.g., insect polarized light navigation, ant path integration) [29,30], migratory bird-specific multimodal perception and large-scale terrain environment adaptation are more useful in unmanned agricultural systems [22]. Compared to insect-based bionic navigation, the following observations are noted:
  • Insect-dependent polarized light modes are unstable in agricultural overcast and hazy environments [30];
  • Migratory birds fuse vision, geomagnetism, and somatosensory senses to possess stronger environmental generalization [23,26];
  • Bird neural systems are robust and modellable in navigation switching strategies, which are easy to map to filter parameter adjustment [31].
The navigation of autonomous agricultural seeders is a critical task that requires precise and robust estimation of their own state to ensure efficient and accurate operation in dynamic and often unpredictable environments. The recent advancements in Kalman filtering technology demonstrates its ability to handle nonlinear and partially known dynamic systems. For instance, Revach et al. [32] introduced KalmanNet, a method that combines neural networks with Kalman filtering to effectively handle non-linear dynamics when only partial information is available. Similarly, Harl et al. [33] developed a neural network-based modified state observer to estimate uncertainties in orbit determination, demonstrating the potential of neural networks to enhance state estimation in the presence of model uncertainties. Furthermore, Zhou et al. [34] proposed an adaptive order-switching Kalman filter that leverages deep neural networks for nonlinearity detection, offering a mechanism to balance computational efficiency and estimation accuracy by dynamically adjusting the filter’s complexity. In this paper, we propose a bionic extended Kalman filter algorithm for a planting machine that can be used by the planting machine to estimate its own state in real time under the complex environment. The main innovations of this paper are as follows:
  • A mathematical model of the neural navigation mechanism of migratory birds, including a proposed sensory weight mapping formula with structural fusion of state residuals;
  • A time-varying fusion and dynamic noise adjustment mechanism, combined with soft switching idea to improve robustness;
  • Fusion of deep learning classifiers to realize online environment recognition and parameter self-tuning, breaking through the limitations of traditional EKF that requires manual parameter tuning.
The rest of this paper is organized as follows: Section 2 models the system of plant protection machine, Section 3 introduces the bionic EFK algorithm, Section 4 verifies the performance of the algorithm through comparative experiments, and Section 5 concludes the study and proposes future application scenarios.

2. System Modeling

2.1. Definition of State Vector

In order to accurately describe the motion characteristics of the agricultural plant protection machine in complex terrain, the state vector is designed as a nine-dimensional vector containing position, velocity, and attitude. The state vector x is defined as follows:
x   =   p x p y p z v x v y v z ϕ θ ψ
where p x ,     p y ,   p z (unit: meter) denotes the position coordinates of the planting machine in 3D space; v x ,   v y ,   v z (unit: m/s) denotes the velocity components along the three axes; and ϕ ,     θ ,     ψ (unit: radian) denotes the roll angle, pitch angle, and yaw angle, respectively, which are used to describe the spatial orientation of the planting machine. This state vector design can comprehensively capture the motion state of the planting machine, laying the foundation for subsequent dynamic modeling and state estimation.

2.2. Nonlinear Dynamic Model

The motion of agricultural plant protection aircraft in complex terrain (such as hills or mountains) exhibits significant nonlinear characteristics, so a nonlinear dynamic model is used to describe the change of its state with time. The dynamic model is defined as follows:
x ˙   =   f ( x , u )
where u is the control input vector containing the three-axis acceleration a x , a y , a z in meters per second2 and the angular velocity p ,   q ,   r in radians per second, which are supplied by the inertial measurement unit IMU. The nonlinear function f ( x , u ) is specifically defined as follows:
f ( x , u )   =   v x v y v z a x a y a z p   +   q s i n ϕ t a n θ   +   r c o s ϕ t a n θ q c o s ϕ     r s i n ϕ q s i n ϕ / c o s θ   +   r c o s ϕ / c o s θ
The function describes the change rule of the state vector, and the position component is updated with velocity p ˙ x   =   v x ,   p ˙ y = v y ,     p ˙ z   =   v z to indicate the cumulative change of position with velocity. The velocity component is updated with acceleration v ˙ x   =   a x ,     v ˙ y   =   a y ,   v ˙ z   =   a z to indicate the effect of acceleration on velocity, and the attitude update equation is based on Euler’s angular kinematics, which calculates the rate of change of the attitude angle through the angular velocity p ,     q ,     r . This nonlinear model can accurately describe the dynamic behavior of the plant protection aircraft in complex environments.

2.3. Measurement Model

The measurement model is used to associate sensor observations with state vectors by integrating data from GPS and laser SLAM to provide accurate observation information. Measurement vector z k is defined as follows:
z k   =   h ( x k )   +   v k
where the measurement vector z k contains 3D position measurements provided by GPS, position and attitude measurements provided by SLAM, and velocity measurements provided by IMU (obtained by integration); h ( x k ) is a nonlinear measurement function representing the theoretical mapping relationship between the state vector x k and the measurement vector z k ; and v k is the measurement noise obeying a zero-mean Gaussian distribution with a covariance matrix R. This model provides a reliable observation basis for state estimation by fusing multi-source sensor data.

3. Biomimetic Extended Kalman Filter (EKF) Algorithm

3.1. Standard Extended Kalman Filter

The standard extended Kalman filter (EKF) is a widely used method for state estimation in nonlinear systems, providing a recursive solution by linearizing the system dynamics and measurement models around the current estimate. The algorithm consists of two main steps: prediction and update.

3.1.1. Prediction Step

The prediction step of the extended Kalman filter (EKF) predicts the next moment state of the plantation machine through a nonlinear dynamic model and evaluates its uncertainty through the covariance matrix. The state prediction equation is expressed as follows:
x ^ k   =   f ( x ^ k     1 , u k )
where x ^ k is the a priori state estimate, x ^ k     1 is the a posteriori state estimate from the previous moment, and u k is the current control input, including the acceleration and angular velocity measured by the IMU. The function is calculated by the fourth-order Runge-Kutta method.
The covariance prediction equation is expressed as follows:
P k   =   F k P k     1 F k T   +   Q k
where P k     1 is the covariance matrix of the previous moment, which describes the uncertainty of the state estimation; Q k is the process noise covariance matrix, which reflects the effect of system noise; and F k   =   f x | x ^ k     1 is the state transfer Jacobian matrix. It is defined as follows:
F k = 0 3   ×   3 I 3   ×   3 0 3   ×   3 0 3   ×   3 0 3   ×   3 0 3   ×   3 0 3   ×   3 0 3   ×   3 Φ ˙ Φ
where, Φ   =   [ ϕ , θ , ψ ] T . The Jacobi matrix for the pose part is expressed as follows:
Φ ˙ / Φ   =   q c o s ϕ t a n θ     r s i n ϕ t a n θ ( q s i n ϕ   +   r c o s ϕ ) s e c 2 θ 0 q s i n ϕ     r c o s ϕ 0 0 q c o s ϕ / c o s θ     r s i n ϕ / c o s θ ( q s i n ϕ   +   r c o s ϕ ) t a n θ / c o s θ 0
This matrix reflects the dynamic coupling between the state variables by calculating the partial derivatives of the nonlinear function f ( x , u ) , ensuring that the prediction step accurately captures the nonlinear properties.

3.1.2. Update Steps

The update steps for the EKF use sensor observations to correct the predicted state and optimize the state estimation accuracy. The state update equation is expressed as follows:
x ^ k   =   x ^ k   +   K k ( z k     h ( x ^ k ) )
where x ^ k is the a posteriori state estimate, and z k     h ( x ^ k ) is the measurement residual, which represents the deviation of the observed value from the predicted value. The measurement prediction is calculated by h ( x ^ k ) , which generates the expected observation based on the a priori state. K k is the Kalman gain. The Kalman gain is calculated as follows:
K k   =   P k H k T ( H k P k H k T   +   R ) 1
where H k   =   h x | x ^ k is the Jacobi matrix of the measurement function. It is defined as follows:
H k   =   I 3   ×   3 O 3   ×   3 O 3 × 3 I 3   ×   3 O 3   ×   3 O 3   ×   3 O 3   ×   3 O 3   ×   3 I 3   ×   3
This matrix maps the state vectors to the observation space, reflecting the direct effect of IUM, GPS, and SLAM measurements on position and attitude; R is the measurement noise covariance matrix, which describes the sensor noise characteristics. The covariance update equation is expressed as follows:
P k   =   ( I     K k H k ) P k
where I is the unit matrix, and the updated covariance matrix P k reduces the uncertainty. This step optimizes the state estimation by fusing the observations and adapts to the complexity of the nonlinear system.

3.2. Bio-Inspired Adaptive Mechanisms

Building upon the standard EKF described in Section 3.1, this subsection introduces the novel bio-inspired enhancements inspired by the multimodal navigation strategies of migratory birds. These adaptations improve the robustness and accuracy of state estimation in complex agricultural environments by dynamically adjusting sensor fusion weights, process noise covariance, and measurement noise covariance.

3.2.1. Sensor Fusion Weights Adjustment Model

To optimize the fusion effect of multi-source sensor data, this paper proposes a dynamic weight adjustment model based on the neural mechanism of migratory birds, which abstracts a set of engineering-implementable sensory selection mechanisms from the multimodal navigation behavior of migratory birds. Biological studies have shown that migratory birds assign different navigation weights to different sensory channels (visual, geomagnetic, and somatosensory) according to the environmental conditions during migration, and their strategy switching and neural activities are reflected in the dynamic changes of neural firing patterns in multisensory integration areas (e.g., the vestibular system, the optic cortex, and the parietal cortex) at the physiological level. Although this regulation has not been uniformly modeled as a specific neurodynamic system, its behavioral response patterns have been confirmed to be predictable by neuroecological experiments. In this paper, we adopt an abstract modeling approach at the level of behavioral mechanisms to transform the migratory birds’ prioritization of sensory channels in different environments into a set of soft selection weighting formulas. Let the three sensory channels be Gvision (visual landmarks), Gmag (geomagnetic navigation), and Gvest (somatosensory balance), with sensory weights w1, w2, and w3, respectively, and their weights are assigned at any time t. The weights are then calculated as follows:
w i ( t )   =   exp ( α i s i ( t ) ) j   =   1 3 exp ( α j s j ( t ) )
where s i ( t ) is the confidence signal strength of the ith sensory channel and α i is the sensitivity coefficient of the corresponding channel. This mechanism is equivalent to a softmax neural strategy, which is able to dynamically perceive the environmental advantages and disadvantages and switch the dominant sensory channel.
In the engineering implementation, s i ( t ) can be estimated from the historical residual variance, and α i can be learned from an online learning module. This modeling mechanism implements a formal mapping from the migratory bird neural strategy to adaptive filter weight assignment. The conceptual schematic is shown in Figure 2.

3.2.2. Dynamic Adjustment Model for Noise Covariance

Based on the behavior of migratory birds in adjusting their navigation strategies under different weather conditions, a mechanism for dynamically adjusting the process noise covariance is proposed. The dynamic adjustment formula is expressed as follows:
Q k   =   Q 0   +   α var ( u k )
where Q 0 is the underlying noise covariance matrix; var ( u k ) represents the inherent noise of the system and the variance of the control inputs (e.g., acceleration and angular velocity), reflecting the strength of the environmental perturbation; and α is the adjustment coefficient controlling the magnitude of the adjustment.
In the neural mechanism of migratory birds, if the visual or geomagnetic trust decreases, the system will rely more on the feedback from the somatosensory system. The somatosensory feedback is proprioceptive in nature and has a greater impact on the prediction component. Therefore, migratory birds will increase the tolerance for process uncertainty when sensory trust is unclear. When the overall reliability of the external sensory observations decreases (e.g., a severe failure of the GPS), it should be boosted by α to enhance the process noise covariance to avoid overconfidence in the prediction results. The acquisition of the conditioning factor α depends on the assignment of migratory bird sensory weights, thus creating an overall confidence indicator:
w sensor   =   i   =   1 n γ i w i
where w i is the i-th sensory weight, γ i is the base confidence factor for each sense (e.g., 0.6 for SLAM, 0.3 for GPS, and 0.1 for IMU), and w sensor represents the overall confidence in the current system’s observations of the senses. Then, α is defined as follows:
α   =   α max ( 1     w sensor )
This formulation is based on behavioral abstraction modeling of migratory bird sensory trust switching behavior and reflects an engineering-controlled linear inverse relationship. When overall sensory trust w sensor is higher (i.e., the sensory channel on which the system is currently relying is more trustworthy), α should be smaller, the process noise covariance is lower, and the prediction process is more “confident”. In contrast, when sensory trust credibility is low, α rises, and the filter becomes more resilient to potential state drifts, increasing robustness.
The design of the dynamic tuning mechanism maps the bionic principle of migratory bird navigation. The differential setting of the maximum tuning coefficient α m a x simulates the migratory bird’s trust in senses under different environments. A low value of α m a x represents trust in senses under stable environments, while a high value of α corresponds to distrust in senses under harsh conditions. This mapping from biological behavior to algorithmic parameters is essentially to transform the robustness mechanism formed by natural evolution into adaptive rules of engineering systems. In practical engineering, the value of the adjustment coefficient α m a x should be determined in combination with the dynamic characteristics of the system task and the complexity of the environment. For agricultural scenarios that prioritize accuracy (e.g., open field operation), the value range is generally 0.05–0.20 to ensure the stability of state propagation. For applications with higher robustness requirements (e.g., hilly woodland, post-disaster search, etc.), the value can be appropriately increased to 0.20–0.50 to enhance tolerance to sensor failure and environmental perturbation. In highly dynamic systems, the value of the adjustment factor should be determined in conjunction with the dynamic characteristics of the system task and the complexity of the environment. In highly dynamic systems (e.g., UAVs or fast maneuvering robots), where the process changes drastically, it is usually necessary to set α m a x between 0.30 and 0.80 to ensure that the filter does not become overconfident in fast response. This is shown in Table 1.

3.2.3. Time-Varying Measurement Noise Estimation

A time-varying measurement noise covariance estimation method is proposed to dynamically assess the credibility of each sensory information based on migratory birds’ real-time perception of environmental feedback (e.g., changes in wind speed and airflow) through the nervous system. The fused residuals are formulated as follows:
r k   =   i   =   1 n w i z k ( i )     h ( i ) ( x ^ k )
where i represents different sensors.
The measurement noise covariance estimation equation is expressed as follows:
R k   =   ( 1     β ) R k     1   +   β Cov [ r k ]
where R k     1 is the covariance of the measurement noise at the previous moment, and β is a smoothing factor that controls the update rate. The selection of β requires a balance between stability and adaptability. Usually, in environments with relatively stable noise characteristics (such as plain terrain under clear weather), the value of β is small, ranging from 0.01 to 0.1, to prevent the filter from overreacting to temporary noise fluctuations or outliers, thereby maintaining the stability of the estimation. However, in scenarios with rapidly changing noise characteristics (such as windy and rainy weather in hilly terrain), a larger β value is required to accelerate the adjustment speed of R k , so that the filter can quickly adapt to new noise conditions and maintain the accuracy of state estimation. In practical applications, the selection of β can be determined through empirical testing or real-time performance monitoring. For example, if the estimation error of the filter increases over time, it may indicate that the current value of β is not sufficient for R k to quickly adapt to noise changes. In this case, β can be appropriately increased. On the contrary, if the filter exhibits instability or is overly sensitive to noise, β should be reduced to enhance stability. The method for determining the smoothing factor is based on sliding window statistics. Using the statistical characteristics of the residuals from the last 10 measurements, if the mean of the residuals is small (representing an environment with slowly changing noise), the value of β is reduced to reduce the sensitivity of the filter to short-term disturbances. If the statistical residual mean is large (representing an environment with rapidly changing noise), the value of β is increased to ensure that the update speed is slowed down when the noise fluctuates greatly, making the filter more adaptable. The adjustment of the β value helps the filter maintain a low average position error and improves the robustness of the algorithm.

4. Experimental and Simulation Analysis

In order to comprehensively verify the performance of the proposed bionic EKF algorithm, this section compares and analyzes its performance with traditional algorithms in complex agricultural environments using multi-scenario simulation experiments and introduces the UKF, the PF, and a bionic navigation algorithm based on the path integral as comparisons. UKF uses the traceless transformation to replace the Jacobi computation, which improves the nonlinear adaptability. PF uses particle sampling to characterize the state distribution, which is robust but with high computational complexity. The bionic path integral algorithm imitates the insect to estimate the relative displacement, which is suitable for short-distance navigation. In this paper, the algorithms achieve self-adaptation to the complex environment by dynamically adjusting the process noise covariance and time-varying measurement noise covariance and optimizing the sensor fusion weights. The evaluation index is centered on the mean position error (MPE), supplemented by algorithm robustness analysis. In order to realize the ability to automatically adapt to the environment, an LSTM-based environment classification module is introduced. The input is the sensor residual time series, and the output is the current scene category, which is further mapped to the adjustment of α and β parameters. The structure of the classifier is described as follows: input layer (time window = 10 steps) → two-layer LSTM (hidden element = 32) → fully connected mapping → softmax output. Predictive labeling controls weighting strategy switching to reach fully online adjustment.
The effectiveness of the bionic mechanism is verified by comparing the performance of the algorithm in different scenarios. The experimental design covers different combinations of terrain and weather to simulate the variable conditions in real agricultural operations. The simulation platform is implemented based on Python 3.9, and each combination of environments is run for 500 steps to ensure the statistical significance of the results.

4.1. Experimental Design

The experimental environment is divided into two types of terrain, plains and hills, and combined with three types of weather conditions, sunny, heavy rain, and windy and rainy, to form a total of six test scenarios. The experimental data utilized in this study are generated through simulations in Python 3.9, employing synthetic datasets that model real-world sensor readings from GPS, IMU, and laser SLAM under varying environmental conditions. Specifically, the data consist of time-series sequences (500 steps per run, with a step duration of 0.1 s simulating 50 s of operation) including position (x, y, z in meters), velocity (m/s), attitude (radians), and control inputs (acceleration in m/s2 and angular velocity in rad/s). These datasets are synthesized using Gaussian noise models augmented with multiplicative factors to replicate physical disturbances. Baseline noise is drawn from zero-mean distributions with covariances calibrated from real agricultural sensor benchmarks (derived from field tests) [3] and then amplified as per Table 2 to account for terrain (e.g., hills introducing occlusion via ray-tracing simulation) and weather (e.g., rain adding multipath via random perturbations up to ±30%). Random perturbations are generated using NumPy’s random normal function to introduce variability, ensuring statistical relevance to unstructured farmland scenarios like those in hilly Chinese orchards or Midwestern US plains [5]. The noise amplification factor of the sensor is shown in Table 2.

4.2. Simulation Results and Analysis

The experimental results, including mean position errors (MPE), time consumption, and error variance, are presented in Figure 3 (comparison of average position error across scenarios), Table 3 (single-step time consumption in milliseconds), and Table 4 (MSE and 95% confidence intervals), demonstrating the algorithm’s superior accuracy and efficiency in simulated complex agricultural environments. These metrics are derived from averaged outcomes over 100 Monte Carlo runs per scenario to ensure statistical reliability.
The error range of this paper’s algorithm in six environments is 0.39 m–1.20 m, which shows good environmental adaptability and robustness of perceptual fusion. Although the PF algorithm is slightly better than this paper’s algorithm in terms of error, the gap in most tests is not significant. In terms of the computational resource consumption, it is much higher than other methods. UKF performs slightly better than this paper’s algorithm in some highly nonlinear scenarios, but the lack of multi-sensor weight fusion capability causes its error to increase rapidly in harsh environments, up to 1.38 m. The path integral method, on the other hand, has consistently higher errors (up to 2.43 m) due to the absence of an external observation correction mechanism and expands rapidly with the terrain ups and downs and meteorological deterioration.
In addition, in terms of average time consumption, the overall computational complexity of this paper’s algorithm is kept at O(n) level due to the fact that it only needs to perform one Kalman update and the fusion weight preprocessing module is a matrix-weighting operation. In contrast, UKF needs to propagate 2n + 1 sigma points, and PF needs to maintain hundreds or even thousands of particles, which are 1.46 times and 8.0 times of the algorithm of this paper in terms of time consumption, respectively. Therefore, the algorithm in this paper is more suitable for embedded system deployment with high real-time requirement while maintaining high accuracy.

4.3. Computational Efficiency Evaluation

In order to verify the stability of the algorithm under complex perturbation conditions, this paper analyzes both theoretical and experimental aspects. First, the state error is constructed as follows:
e ( t ) = x true ( t ) x ^ ( t )
where x true ( t ) is the true state of the system at moment t; x ^ ( t ) is the filter’s estimate of the state.
Construct the Lyapunov candidate function as follows:
V ( t ) = e ( t ) T P 1 e ( t )
where P is the state covariance matrix.
Differentiating the state update formulation of the EKF yields that the system is asymptotically stable if there exists η > 0 such that d V ( t ) d t   <   η e ( t ) 2 holds.
The calculation under each scenario yields η > 0 and the error bound converges, proving that the filtering process does not diverge.
The stability of the algorithm is further verified using Monte Carlo simulation. The error variance of this paper’s algorithm is lower than that of the UKF and the path integral method, while its confidence interval is narrower and close to that of the PE algorithm, indicating that the estimation results are more concentrated and more stable. This result proves that the bionic adaptive mechanism can effectively deal with the environmental perturbations and avoid the dispersion of state estimation. Although the time complexity of the algorithm is higher than that of the path integral algorithm due to the introduction of the dynamic adjustment mechanism, the single-step execution time is only 26% higher than that of the path integral algorithm and much lower than that of the PF algorithm, which is extremely time-consuming. Although the computational efficiency of the algorithm is slightly increased compared with the path integral algorithm, the single-step execution time is still controlled within 1 ms, which fully meets the real-time control requirements of 10 Hz for plant protection machines. This small computational overhead is exchanged for the significant improvement in accuracy in complex environments, which reflects the rationality of the design of the algorithm and its applicability to engineering. In the future, the execution time can be further shortened by hardware acceleration or code optimization to meet the demand of higher frequency control.

5. Results

The bionic EKF algorithm proposed in this paper is optimized by sensor fusion to achieve high positioning accuracy in complex agricultural environments. Experimental data show that the average position error in hilly and windy rainy scenarios is reduced by 24% compared to the UKF algorithm and 50% compared to the path integration algorithm, while the single-step execution time consumption is still controlled within 1 ms, which fully meets the real-time control requirements of 10 Hz for plantation machines, with lower error variance and more stable performance. Its design is inspired by the multimodal information integration strategy of migratory birds, which demonstrates the advantages of bionic strategy in dealing with complex scenes. The slight sacrifice in computational efficiency of the algorithm is exchanged for a significant increase in robustness, which provides reliable technical support for the autonomous navigation of agricultural plant protection machines.
In summary, the bionic fusion EKF algorithm proposed in this paper balances positioning accuracy, perceptual adaptivity, and computational efficiency in unstructured and multi-disturbance environments and is suitable for the following complex navigation environments:
  • Forestry monitoring: e.g., fire patrol in mountainous areas, mapping of pest and disease distribution;
  • Detection of disaster areas: such as semi-autonomous search and localization of collapsed areas after earthquakes;
  • Special terrain transportation robots: such as snow, desert, and other environments in the path estimation.
All of the above applications require stable navigation in scenes with large sensor uncertainty and poor visibility, and the bionic EKF provides an effective solution for this.

Author Contributions

Conceptualization, Z.Z. and J.S.; methodology, Z.Z.; software, Z.Z.; validation, Z.Z., J.S. and Y.H.; formal analysis, Z.Z.; investigation, Y.H.; resources, Z.Z.; data curation, Z.Z.; writing—original draft preparation, Z.Z.; writing—review and editing, Z.Z.; visualization, Z.Z.; supervision, J.S.; project administration, J.S.; funding acquisition, J.S. All authors have read and agreed to the published version of the manuscript.

Funding

This work was supported by the Jilin Provincial Scientific and Technological Development Program (YDZJ202503CGZH040).

Conflicts of Interest

The authors declare no conflict of interest.

References

  1. Kondoyanni, M.; Loukatos, D.; Maraveas, C.; Drosos, C.; Arvanitis, K.G. Bio-Inspired Robots and Structures toward Fostering the Modernization of Agriculture. Biomimetics 2022, 7, 69. [Google Scholar] [CrossRef] [PubMed]
  2. Wang, Y.; Yang, W. Research Progress on Autonomous Navigation Technology for Multiple Agricultural Scenarios. Comput. Electron. Agric. 2023, 214, 108351. [Google Scholar] [CrossRef]
  3. Han, X.; Kim, H.J.; Jeon, C.W. GNSS/IMU Integrated Navigation for Agricultural Machinery Based on Fuzzy Adaptive Finite Impulse Response Kalman Filter Algorithm. Comput. Electron. Agric. 2021, 191, 106541. [Google Scholar] [CrossRef]
  4. Zhang, J.; Liu, G. Application of Updated Sage–Husa Adaptive Kalman Filter in the Navigation of a Translational Sprinkler Irrigation Machine. IFAC-Pap. 2019, 52, 333–338. [Google Scholar] [CrossRef]
  5. Li, X.; Zhang, W. Autonomous Navigation Method for Agricultural Robots in High-Tunnel Cultivation Environments. Comput. Electron. Agric. 2022, 203, 107107. [Google Scholar] [CrossRef]
  6. Gonzalez, D.; Ruggiero, V. Development of a Navigation System for Smart Farms. IFAC-Pap. 2018, 51, 1–6. [Google Scholar] [CrossRef]
  7. Zhang, Q.; Chen, Y. Development of an Automatic Navigation System for Following Agricultural Machinery. Comput. Electron. Agric. 2019, 158, 351–360. [Google Scholar] [CrossRef]
  8. Wang, X.; Li, Y. Design and Experiment of a Field Management Robot and Its Navigation Control System for Agriculture. Agronomy 2024, 14, 654. [Google Scholar] [CrossRef]
  9. Bar-Shalom, Y.; Li, X.R. Comparison of Kalman Filters for Inertial Integrated Navigation. Sensors 2019, 19, 1786. [Google Scholar] [CrossRef]
  10. Webb, B. Biorobotic Navigation. Robot. Auton. Syst. 2000, 30, 159–177. [Google Scholar] [CrossRef]
  11. Chahl, J.S.; Mizutani, A. A Biomimetic Radar System for Autonomous Navigation. Sensors 2019, 19, 252. [Google Scholar] [CrossRef]
  12. Bianchi, G.; Lanzetti, L.; Mariana, D.; Cinquemani, S. Bioinspired Design and Experimental Validation of an Aquatic Snake Robot. Biomimetics 2024, 9, 87. [Google Scholar] [CrossRef]
  13. He, X.; Li, X.; Wang, X.; Meng, F.; Guan, X.; Jiang, Z.; Yuan, L.; Ba, K.; Ma, G.; Yu, B. Running Gait and Control of Quadruped Robot Based on SLIP Model. Biomimetics 2024, 9, 24. [Google Scholar] [CrossRef]
  14. Duman, E.; Uysal, M.; Alkaya, A.F. Migrating Birds Optimization: A new metaheuristic approach and its performance on quadratic assignment problem. Inf. Sci. 2012, 217, 65–77. [Google Scholar] [CrossRef]
  15. Oral, M.; Duman, E. Enhanced migrating birds optimization algorithm for optimization problems in different domains. Ann. Oper. Res. 2024, 351, 455–488. [Google Scholar] [CrossRef]
  16. Zhang, Z.; Wang, Y.; Li, J. An Improved Migratory Birds Optimization Algorithm for Closed-Loop Supply Chain Network Design under Uncertainty. PLoS ONE 2024, 19, e0306294. [Google Scholar] [CrossRef]
  17. Pan, Q.K.; Tasgetiren, M.F.; Suganthan, P.N.; Chua, T.J. A discrete artificial bee colony algorithm for the lot-streaming flow shop scheduling problem. Inf. Sci. 2011, 181, 2455–2468. [Google Scholar] [CrossRef]
  18. Al-Omary, A.; Jafar, A.; Al-Khudairi, O. Migratory birds-inspired navigation system for unmanned aerial vehicles. In Proceedings of the 2017 International Conference on Electrical and Computing Technologies and Applications (ICECTA), Ras Al Khaimah, United Arab Emirates, 21–23 November 2017; IEEE: Piscataway, NJ, USA, 2017; pp. 1–6. [Google Scholar] [CrossRef]
  19. Du, Y.; Zhang, Q. Review of Bionic Polarized Light Navigation Sensors. Sensors 2023, 23, 5848. [Google Scholar] [CrossRef]
  20. Mourad, K.; Foppen, R.P. Simulated Experiments Testing Geomagnetic Navigation Strategies During Long-Distance Bird Migration. Mov. Ecol. 2021, 9, 48. [Google Scholar] [CrossRef]
  21. Guilford, T.; Taylor, G.K. The Navigation of Migratory Birds: Insights from Insect-Inspired Studies. Integr. Comp. Biol. 2014, 54, 683–692. [Google Scholar] [CrossRef]
  22. Bairlein, F.; Norris, D.R.; Voigt, C.C. New frontiers in bird migration research. Curr. Biol. 2022, 32, R1097–R1107. [Google Scholar] [CrossRef]
  23. Chernetsov, N. How Migrating Birds Use Quantum Effects to Navigate. Scientific American 2022. Available online: https://www.scientificamerican.com/article/how-migrating-birds-use-quantum-effects-to-navigate/ (accessed on 19 June 2025).
  24. Mouritsen, H. True navigation in birds: From quantum physics to global migration. J. Zool. 2014, 293, 73–82. [Google Scholar] [CrossRef]
  25. Guilford, T.; Åkesson, S.; Gagliardo, A.; Holland, R.A.; Mouritsen, H.; Muheim, R.; Wiltschko, R.; Wiltschko, W.; Bingman, V.P. Migratory navigation in birds: New opportunities in an era of fast-developing tracking technology. J. Exp. Biol. 2011, 214, 3705–3712. [Google Scholar] [CrossRef] [PubMed]
  26. Bingman, V.P.; Cheng, K. The Neural Basis of Long-Distance Navigation in Birds. Annu. Rev. Physiol. 2016, 78, 133–154. [Google Scholar] [CrossRef]
  27. MacDonald, C.J.; Tonegawa, S. On a Search for a Neurogenomics of Cognitive Processes Supporting Avian Migration and Navigation. Integr. Comp. Biol. 2020, 60, 967–979. [Google Scholar] [CrossRef] [PubMed]
  28. Hein, C.M.; Zapka, M.; Mouritsen, H. Comparison of Visually Guided Flight in Insects and Birds. Front. Neurosci. 2018, 12, 157. [Google Scholar] [CrossRef]
  29. Pritchard, D.J.; Healy, S.D. Taking an insect-inspired approach to bird navigation. Learn. Behav. 2018, 46, 7–22. [Google Scholar] [CrossRef]
  30. Serres, J.R.; Ruffier, F. Towards a Predictive Bio-Inspired Navigation Model. Information 2021, 12, 100. [Google Scholar] [CrossRef]
  31. Fischer, J.; Kutsch, W. Fast and Robust Bio-inspired Teach and Repeat Navigation. arXiv 2020, arXiv:2010.11326. [Google Scholar] [CrossRef]
  32. Revach, G.; Shlezinger, N.; Ni, X.; Escoriza, A.L.; Van Sloun, R.J.; Eldar, Y.C. KalmanNet: Neural Network Aided Kalman Filtering for Partially Known Dynamics. IEEE Trans. Signal Process. 2022, 70, 1532–1547. [Google Scholar] [CrossRef]
  33. Harl, N.; Rajagopal, K.; Balakrishnan, S.N. Neural Network Based Modified State Observer for Orbit Uncertainty Estimation. J. Guid. Control. Dyn. 2013, 36, 1194–1209. [Google Scholar] [CrossRef]
  34. Zhou, X.; Qiao, D.; Li, X. Adaptive Order-Switching Kalman Filter for Orbit Determination Using Deep-Neural-Network-Based Nonlinearity Detection. J. Spacecr. Rocket. 2023, 60, 1724–1741. [Google Scholar] [CrossRef]
Figure 1. Schematic diagram of an agricultural plant protection spraying machine.
Figure 1. Schematic diagram of an agricultural plant protection spraying machine.
Biomimetics 10 00543 g001
Figure 2. Schematic diagram of the concept of multisensory integration.
Figure 2. Schematic diagram of the concept of multisensory integration.
Biomimetics 10 00543 g002
Figure 3. Comparison of average position error.
Figure 3. Comparison of average position error.
Biomimetics 10 00543 g003
Table 1. Dynamic adjustment of parameters.
Table 1. Dynamic adjustment of parameters.
Environmental CombinationsMaximum Adjustment Factor
plains + sunny0.05
plains + heavy rain0.20
plains + windy and rainy0.35
hills + sunny0.12
hills + heavy rain0.35
hills + windy and rainy0.50
Table 2. Noise amplification factor.
Table 2. Noise amplification factor.
Environmental CombinationsTitle 2Title 3Title 4
plains + sunny1.01.01.0
plains + heavy rain3.0 + random perturbation1.01.0
plains + windy and rainy3.0 + random perturbation4.0 + random perturbation2.8 + random perturbation
hills + sunny5.01.03.2
hills + heavy rain5.0 × 3.01.03.2 × 1.0
hills + windy and rainy5.0 × 3.04.0 + random perturbation3.2 × 2.8
Table 3. Comparison of algorithm time consumption.
Table 3. Comparison of algorithm time consumption.
ArithmeticSingle-Step Time-Consuming (Milliseconds)
Bio-EKF0.97
UKF1.42
PF7.83
Path0.71
Table 4. Comparison of error analysis.
Table 4. Comparison of error analysis.
ArithmeticMSE (m2)Width of 95% Confidence Interval (m)
Bio-EKF0.391.13
UKF0.801.84
PF0.200.98
PATH3.862.35
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.

Share and Cite

MDPI and ACS Style

Zhou, Z.; Huang, Y.; Sun, J. Migratory Bird-Inspired Adaptive Kalman Filtering for Robust Navigation of Autonomous Agricultural Planters in Unstructured Terrains. Biomimetics 2025, 10, 543. https://doi.org/10.3390/biomimetics10080543

AMA Style

Zhou Z, Huang Y, Sun J. Migratory Bird-Inspired Adaptive Kalman Filtering for Robust Navigation of Autonomous Agricultural Planters in Unstructured Terrains. Biomimetics. 2025; 10(8):543. https://doi.org/10.3390/biomimetics10080543

Chicago/Turabian Style

Zhou, Zijie, Yitao Huang, and Jiyu Sun. 2025. "Migratory Bird-Inspired Adaptive Kalman Filtering for Robust Navigation of Autonomous Agricultural Planters in Unstructured Terrains" Biomimetics 10, no. 8: 543. https://doi.org/10.3390/biomimetics10080543

APA Style

Zhou, Z., Huang, Y., & Sun, J. (2025). Migratory Bird-Inspired Adaptive Kalman Filtering for Robust Navigation of Autonomous Agricultural Planters in Unstructured Terrains. Biomimetics, 10(8), 543. https://doi.org/10.3390/biomimetics10080543

Article Metrics

Back to TopTop