You are currently viewing a new version of our website. To view the old version click .
Agronomy
  • Article
  • Open Access

Published: 12 October 2025

A LiDAR SLAM and Visual-Servoing Fusion Approach to Inter-Zone Localization and Navigation in Multi-Span Greenhouses

,
and
Jiangsu Key Laboratory of Embodied Intelligent Robot Technology, College of Mechanical and Electrical Engineering, Soochow University, Suzhou 215123, China
*
Author to whom correspondence should be addressed.
Agronomy2025, 15(10), 2380;https://doi.org/10.3390/agronomy15102380 
(registering DOI)
This article belongs to the Section Precision and Digital Agriculture

Abstract

Greenhouse automation has become increasingly important in facility agriculture, yet multi-span glass greenhouses pose both scientific and practical challenges for autonomous mobile robots. Scientifically, solid-state LiDAR is vulnerable to glass-induced reflections, sparse geometric features, and narrow vertical fields of view, all of which undermine Simultaneous Localization and Mapping (SLAM)-based localization and mapping. Practically, large-scale crop production demands accurate inter-row navigation and efficient rail switching to reduce labor intensity and ensure stable operations. To address these challenges, this study presents an integrated localization-navigation framework for mobile robots in multi-span glass greenhouses. In the intralogistics area, the LiDAR Inertial Odometry-Simultaneous Localization and Mapping (LIO-SAM) pipeline was enhanced with reflection filtering, adaptive feature-extraction thresholds, and improved loop-closure detection, generating high-fidelity three-dimensional maps that were converted into two-dimensional occupancy grids for A-Star global path planning and Dynamic Window Approach (DWA) local control. In the cultivation area, where rails intersect with internal corridors, YOLOv8n-based rail-center detection combined with a pure-pursuit controller established a vision-servo framework for lateral rail switching and inter-row navigation. Field experiments demonstrated that the optimized mapping reduced the mean relative error by 15%. At a navigation speed of 0.2 m/s, the robot achieved a mean lateral deviation of 4.12 cm and a heading offset of 1.79°, while the vision-servo rail-switching system improved efficiency by 25.2%. These findings confirm the proposed framework’s accuracy, robustness, and practical applicability, providing strong support for intelligent facility-agriculture operations.

1. Introduction

Multi-span greenhouses, recognized for their high space-use efficiency and precise environmental controllability, have emerged as a dominant configuration of facility agriculture []. Concurrent progress in artificial intelligence and robotics has accelerated the adoption of mobile robots in greenhouse operations, advancing the sector from conventional automation toward intelligent production []. As facility agriculture scales and advances, the use of multi-span systems in vegetable, floriculture, and seedling production continues to grow. However, the large footprints of single-structure systems, compressed operational cycle, and stringent quality uniformity requirements make it increasingly difficult for manual inspection, crop protection, and intralogistics to meet the integrated demands for cost, efficiency, and traceability []. Autonomous mobile robots equipped with perception, localization, and planning capabilities thus represent a critical pathway toward enhancing both the efficiency and quality of greenhouse production.
Agricultural robotics has become increasingly integrated with core perception technologies such as Simultaneous Localization and Mapping (SLAM), inertial navigation, and machine vision. Alongside advances in path planning and decision-making, these technologies have converged into closed-loop architectures that encompass perception, localization, mapping, planning, and control. Such integration has emerged as the mainstream paradigm enabling stable autonomous operation of mobile robots across diverse scenarios and ground conditions and represents an inevitable trajectory in the evolution of next-generation agricultural machinery [].
With the deep integration of artificial intelligence and robotics, agricultural mobile robots are taking on an increasing range of tasks, including harvesting [,,], material handling [,], crop protection [,], and monitoring [,]. However, greenhouse environments present unique challenges for robotic localization and navigation due to complex lighting conditions, limited availability of Global Navigation Satellite System (GNSS) signals, and highly repetitive structural patterns [].
To improve robustness in such environments, research has progressed in three principal directions: multi-sensor fusion [], LiDAR-based SLAM [], and semantic mapping []. Kutyrev et al. [] developed an autonomous robotic platform for apple orchards that integrates inertial and GNSS navigation with LiDAR-based obstacle avoidance, which can traverse orchard rows and support concurrent operations such as spraying and mowing. Tsiakas et al. [] proposed a camera-LiDAR fusion method that couples range sensing with semantic segmentation to identify rails and crop rows in greenhouse environments, thereby enabling autonomous row traversal and automated inspection. Gupta et al. [] employed a hybrid U-Net model to enhance weed detection and achieved multi-class weed identification through semantic segmentation, thereby improving weed control technologies. Saati et al. [] presented an improved two-stage path-planning algorithm that achieved superior navigation performance in dynamic, crowded indoor environments.
Although significant advances have been made in prior research, studies on a unified, integrated navigation scheme that simultaneously addresses the distinct characteristics of the intralogistics and cultivation areas in multi-span greenhouses remain limited. In multi-span greenhouses, the intralogistics area is characterized by open space, and autonomous navigation performance is governed by the accuracy of localization and mapping, the quality of path planning, and the effectiveness of motion control and obstacle avoidance strategies. However, glass curtain walls create strong specular reflections and sparse usable features, complicating both LiDAR and vision-based perception. In contrast, the cultivation area offers explicit path constraints via pre-installed rails. Yet, the interleaving of corridors and rails, combined with frequent entry, exit, and rail-switching operations, places stringent demands on track recognition, lateral switching, and stable inter-row traversal. Given the multiplicity of operating scenarios in greenhouses, navigation must switch modes according to subtask objectives. The central challenge for practical deployment is to realize a unified, robust localization–navigation framework that performs consistently across the heterogeneous intralogistics and cultivation environments.
Despite these advances, studies on unified navigation schemes for multi-span greenhouses remain scarce. Existing works typically focus on LiDAR-SLAM optimization in logistics-like open spaces or on vision-based servoing for navigation along predefined rails in cultivation zones. Few have addressed the integration of these approaches into a cross-region framework capable of handling the heterogeneous conditions of intralogistics and cultivation areas. Moreover, the challenge of seamlessly switching between open-space navigation and rail-constrained traversal remains underexplored.
Research on robotic control further highlights this gap. Classical approaches, including kinematic modeling, proportional-integral-derivative (PID) control, and pure-pursuit trajectory tracking, have demonstrated effectiveness in structured field environments. More advanced methods, such as adaptive control, model predictive control (MPC), and reinforcement learning, have been introduced to cope with uncertainties in dynamic operating conditions. However, the unique characteristics of greenhouses, such as glass-induced reflections, narrow passages, and repetitive layouts, restrict the direct transfer of these methods from open-field applications.
To systematically evaluate robotic navigation and control strategies for greenhouse operations, synthesis criteria can be classified into three categories: technical (e.g., mapping accuracy, localization error, computational efficiency), functional (e.g., navigation robustness, rail-switching success rate, obstacle avoidance capability), and operational (e.g., labor savings, adaptability to heterogeneous layouts, ease of system integration). Together, these criteria define the practical requirements for deployment and provide a benchmark for assessing the effectiveness of novel approaches.
Motivated by these challenges, this study develops an integrated localization-navigation framework tailored to multi-span glass greenhouses, combining algorithmic innovations with a versatile robotic chassis. The main contributions are as follows:
(1)
We proposed an integrated cross-region localization-navigation framework that accounted for the distinct characteristics of both the intralogistics and cultivation areas, establishing a coordinated aisle-rail workflow and control strategy.
(2)
In the intralogistics area, we introduced a series of multi-layer optimizations into the LiDAR-Inertial Odometry via Smoothing and Mapping (LIO-SAM) framework, designed to suppress glass-induced reflections and mitigate feature sparsity, thereby enhancing mapping accuracy and strengthening localization robustness. When combined with A-Star global planning and the Dynamic Window Approach (DWA) for local obstacle avoidance, this approach ensured reliable autonomous navigation.
(3)
In the cultivation area, we developed a visual-servo mechanism that coupled YOLOv8n track-center detection with pure pursuit control, enabling cross-ridge rail switching without whole-vehicle steering while ensuring stable inter-row traversal.
(4)
We completed platform integration and field validation, which confirmed improvements in localization accuracy, rail-switching efficiency, and navigation robustness, and further demonstrated the integrated platform’s potential for extension to dynamic obstacle avoidance and multi-robot coordination.

2. Materials and Methods

2.1. Representative Operating Scenarios in Multi-Span Greenhouses

The experimental site is the Nijiawan Greenhouse in Suzhou, Jiangsu Province, China (120.62° E, 31.32° N). As shown in Figure 1, contemporary multi-span greenhouses are organized into two core functional areas that collectively support high-efficiency facility-agriculture workflows: the intralogistics area, typically aligned with glass curtain walls, serves as the hub for material flow and operational scheduling, covering tasks such as the transfer of production inputs and harvested products, as well as non-cultivation activities like transport, loading, unloading, and sorting. The cultivation area forms the main spatial component, equipped with crop-production installations and work aisles. This area is coupled with integrated environmental control systems that maintain optimal microclimatic conditions, ensuring stable production and high quality. Together, these two partitions are complementary and synergistic, forming a complete operational system that enables continuous and standardized greenhouse production.
Figure 1. Multi-span greenhouse scenario: (a) Intralogistics area. (b) Cultivation area.

2.2. Structural Optimization and System Integration

To meet the operational demands of mixed rail and ground surfaces in multi-span greenhouses, we have developed a dual-mode drive chassis with aisle-rail coordination for mobile robots, as shown in Figure 2. The chassis features a composite wheelset architecture that integrates an inner rail drive wheel, an outer ground drive wheel, and a top profile-tracking steering-suspension module. Each component is powered by an independent motor, enabling multimodal motion capabilities, including longitudinal travel, directional turning, and lateral rail-switching. Rail support wheel sets are mounted at the front and rear, while ground-mounted caster wheel assemblies provide additional support, ensuring stable load distribution and postural stability in both rail-running and ground-driving modes. Overall, the chassis maintains reliable ground maneuverability and leverages rail-imposed geometric constraints to enhance localization accuracy and trajectory tracking, providing a robust hardware platform for continuous cross-region operation in greenhouse environments.
Figure 2. Photograph of the mobile robot prototype: (a) 3D model: 1. Rail support wheel set; 2. Rail drive wheel set; 3. Ground-mounted caster wheel set. (b) Manufactured form.
In greenhouse environments, mobile robots were subjected to impact loads when traversing dynamic terrains such as rail entry and exit, which induced postural disturbances and compromised tire-ground adhesion. To alleviate these effects, the drive-wheel connection plate was redesigned with integrated elastic elements, including springs and dampers, forming an energy-storing and shock-buffering linkage structure that absorbed impacts and attenuated vibrations during terrain transitions. Furthermore, to accommodate the lateral maneuverability required for inter-row operations, the chassis wheelset was equipped with a steering motor and a dedicated linkage mechanism, resulting in a wheel-rotation module that enabled efficient reorientation and lateral displacement on inter-row tracks, thereby reducing dependence on whole-vehicle steering during rail-switching maneuvers. Collectively, these enhancements markedly improved the robot’s stability and traversability under critical conditions, including cross-track transitions and inter-row lateral maneuvers. The design of the enhanced profile-tracking steering-suspension module is illustrated in Figure 3.
Figure 3. Profile-tracking steering-suspension module: 1. Steering motor; 2. Steering motor mounting base; 3. Lower connecting component of the steering motor; 4. Intermediate connecting component of the steering motor; 5. In-wheel motor; 6. Suspension system component; 7. Drive wheel mounting plate; 8. Stop pin assembly.
Considering overall performance and economy, this study utilizes a solid-state LiDAR (model Mid-360; Livox, Shenzhen, China) as the primary perception unit for map construction in greenhouse environments. Compared to mechanically scanned LiDARs, this sensor affords low cost, a compact footprint, and high responsiveness, while also supporting Ethernet-based direct interfacing with an Industrial Personal Computer (IPC) to enable time-synchronized acquisition and output of point-cloud data and measurements from the integrated IMU. In parallel, rail identification is carried out using a D415 depth camera (model RealSense D415; Intel Corporation, Santa Clara, CA, USA) to capture structured visual (RGB-D) information. Sensor streams are processed on the IPC to generate target waypoints and trajectory commands, which are transmitted to the low-level controller. At the chassis level, a suspension-drive mechanism is employed to handle mixed rail or ground conditions. A geared DC motor drives longitudinal motion, while a servo motor is used for steering and postural adjustments. The IPC functions as the core control unit, managing real-time multi-sensor data acquisition and timestamp synchronization, environment mapping, rail detection algorithms, motion planning, command dissemination, and system-state monitoring. The overall control architecture is shown in Figure 4.
Figure 4. Control system architecture of the mobile robot for multi-span greenhouses.
This study further summarizes the key performance indicators of the robot under real greenhouse operating conditions. The computing platform, based on IPC (Intel Core i7-10700, 2.9 GHz, 8 cores, 16 GB RAM), enables real-time multi-sensor fusion and SLAM processing, while integration with an NVIDIA GTX 1660 Super GPU (6 GB VRAM) extends the system’s capability to advanced visual perception and deep-learning inference. The sensing suite is energy-efficient, with power consumption of approximately 7 W for LiDAR and 2 W for the depth camera. The chassis incorporates dual 800 W hub servo motors and dual 350 W two-stage reduction steering motors, supporting a maximum payload capacity of 300 kg. In greenhouse environments with mixed rail–ground navigation, the robot sustains continuous operation for approximately 2.5–3.0 h.
In the intralogistics area, the mobile robot must navigate dynamic obstacles, such as logistics equipment and personnel. Upon arrival at the target ridge end in the cultivation area, visual recognition is used for rail alignment. During on-rail operation, the robot follows a straight-line trajectory along the prescribed path. When departing the rail for row switching, a dedicated rotation motor actuates the profile-tracking wheelset to perform lateral rail switching, allowing inter-row or cross-ridge maneuvers while maintaining a nearly constant vehicle orientation. After completing the cross-ridge operation, the wheelset reorients to its nominal state, and the robot resumes longitudinal travel along the rail. This operational strategy enhances the adaptability and ensures continuity of tasks in complex greenhouse environments. The layout of the multi-span greenhouse is shown in Figure 5.
Figure 5. Structural layout of the multi-span greenhouse.

2.3. Global Mapping in the Intralogistics Area via Optimized LIO-SAM

To address the challenges posed by glass-induced reflections and sparse feature availability in the intralogistics area of multi-span greenhouses, this study adopts a fusion scheme integrating a solid-state LiDAR with an IMU and introduces targeted optimizations to the LIO-SAM algorithm [] to improve mapping accuracy and robustness. The original LIO-SAM framework was developed for mechanically rotating LiDARs, where point clouds are sequentially organized by scan lines and acquisition order. Feature extraction and motion-distortion correction for edge and planar points rely on the assumption of local geometric continuity among adjacent points within the same scan line. In contrast, the solid-state LiDAR employs an optical phased array for non-repetitive scanning, generating point clouds without scan-line indices. Consequently, the spatiotemporal adjacency of points cannot be directly mapped to the scan-line order of mechanical LiDARs. Directly applying such data to the unmodified LIO-SAM framework would result in projection-model mismatches and failures in feature extraction.
To address this, we utilize the official driver SDK to republish the raw point cloud in a custom message format, adding precise timestamps and intensity values to each point. This enables subsequent motion de-skewing and temporal resampling. The functionality is implemented in a driver node that performs real-time data acquisition and format conversion. In the front-end preprocessing module, the received custom data are temporally resampled and mapped onto a virtual scanline lattice, where each point is assigned equivalent ring identifiers and column indices. In this way, prior to entering the feature-extraction stage of LIO-SAM, we restore its reliance on scan sequencing and local geometric continuity. Importantly, this adaptation is confined to data ingestion and feature preprocessing, with the back-end optimization and the overall LIO-SAM architecture remaining unmodified. This preserves the real-time performance and modularity of the system while enhancing the applicability of solid-state LiDAR.
To address the decline in mapping accuracy observed in the intralogistics area, we introduce the following enhancements to LIO-SAM within a solid-state LiDAR-IMU fusion framework:
(1)
Preprocessing optimization. An intensity-threshold filter is applied to suppress specular artifacts caused by high-reflectance glass façades, improving point-cloud geometric consistency and feature reliability. Given the low-speed operation in greenhouses, the weight of the IMU preintegration factor is moderately reduced to attenuate high-frequency jitter and slow drift in the estimated trajectory.
(2)
Strengthened feature extraction. An adaptive curvature-thresholding strategy based on distribution quantiles is adopted, designating low-curvature points as planar candidates and high-curvature points as edge candidates. In feature-sparse environments, such as long corridors or open spaces, the thresholds are relaxed to ensure sufficient constraints are included in registration and back-end optimization, maintaining stable performance across diverse scene densities.
(3)
Corridor-prior constraint factor. To address trajectory drift from lateral geometric under-constraint in symmetric corridors, we introduce a handcrafted prior within the factor-graph optimization. Specifically, a weak directional-consistency constraint aligned with the odometry-inferred principal direction is applied, supplemented by a lateral-position regularization term. This suppresses drift caused by structural symmetry and enhances stability and trajectory accuracy in degenerate environments.
(4)
Upgraded mapping and loop closure. The Scan Context module is enhanced by enlarging the search radius and refining the matching criterion, thereby reducing the false-match rate and improving loop-closure robustness. In addition, keyframe intervals are shortened and the local-map cache is extended to improve temporal continuity and spatial coverage, compensating for vertical feature discontinuities due to the narrow vertical field of view of solid-state LiDAR.
(5)
Lightweight implementation and post-processing. To satisfy real-time requirements on embedded platforms, we apply 5:1 keyframe downsampling, which preserves acceptable accuracy given the substantial inter-frame overlap at low robot speeds. Following map construction, interactive_slam is employed for operator-in-the-loop local corrections to remove residual specular artifacts and distortions from glass reflections. The optimized core parameters are presented in Table 1.
Table 1. Reference values for parameter optimization.

2.4. Path Planning for Mobile Robots in the Intralogistics Area

The robot’s path planning and navigation are implemented using the ROS Navigation framework, built on the move_base package. This framework integrates external sensor data with an occupancy-grid representation, offering extensible navigation through plugin-based global and local planners, along with layered costmaps. Adaptive Monte Carlo Localization (AMCL) fuses odometry and LiDAR scans to estimate the robot’s real-time pose within a known map. The resulting localization plays a critical role in updating the global costmap and establishing the initial condition for path planning. Upon receiving a target pose, the A-Star planner generates a connected, cost-optimal global path on the global costmap. The DWA performs real-time optimization of the local trajectory, while LiDAR and IMU observations continuously update the local costmap, improving obstacle avoidance and trajectory tracking in dynamic and confined environments. The resulting path is translated into chassis-executable linear and angular velocity setpoints, which are transmitted via the Controller Area Network (CAN) bus to the low-level controller, enabling closed-loop actuation of the drive and steering subsystems, as shown in Figure 6.
Figure 6. Navigation and motion-control framework of the mobile robot.

2.5. Design of Visual-Servo Inter-Row Rail Switching in the Cultivation Area

To enable inter-row traversal and rail switching in the cultivation area, a rail detection and pure pursuit control strategy based on YOLOv8n was developed. The detection system was implemented using the Ultralytics YOLOv8n framework, whose modular Backbone–Neck–Head architecture provides an effective balance between detection accuracy and inference efficiency []. For dataset construction, images were acquired using a depth camera across multiple time periods and under complex, interference-prone greenhouse conditions, followed by manual annotation with LabelImg software(version 1.8.6). Considering the spatial distribution of rails in planar images, the dataset was categorized into “Left,” “Middle,” and “Right” classes to distinguish among different rails in multi-rail environments and avoid misclassification.
To enhance dataset diversity and improve model generalization, deliberate variations in acquisition conditions were introduced. Specifically, the camera was positioned at an operational height of approximately 0.6 m, with images captured under different inclination angles. The dataset also incorporated diverse illumination conditions, including natural daylight, partial shading, and artificial supplementary lighting, as well as artifacts such as rail-surface reflections, soil residues, foliage occlusion, and background clutter. This variability was intended to strengthen the model’s robustness against environmental disturbances in greenhouse scenarios. A dataset of 1200 images was constructed and divided into training, validation, and test sets at a 7:2:1 ratio. Images were resized to 640 × 640 pixels via bilinear interpolation. Training hyperparameters were determined through grid search, including a batch size of 4, an SGD optimizer (learning rate 0.00251, momentum 0.938, weight decay 0.0006), and 300 training epochs. The resulting model achieved a recall of 98.5%, a precision of 98.6%, an F1-score of 98.5% (balancing sensitivity and accuracy), an mAP@50 of 98.2%, and an mAP@50-95 of 73.9%. These results collectively highlight the high accuracy and robustness of the proposed detection system in rail recognition tasks.
To address the interleaved configuration of inter-row rails and walking aisles in multi-span greenhouses, we implement an aisle-rail coordinated workflow. In terms of hardware, a steering-motor-actuated wheelset rotation mechanism is mounted above the drive wheel, allowing a 90° reorientation to realize lateral motion. This allows the robot to directly insert into adjacent rails without reorienting the vehicle body, thereby improving cross-ridge efficiency and operational continuity, as shown in Figure 7. The rail-entry sequence proceeds as follows. First, the robot aligns parallel to the target rail in the intralogistics aisle, and the host IPC issues a CAN command to rotate the steering motor, switching the wheelset to a lateral configuration. Next, the drive wheels perform lateral translation while maintaining the vehicle’s attitude, positioning the chassis at the desired row. A depth camera, coupled with YOLOv8n, performs real-time rail detection and extracts the rail-center coordinates. Once the detection is within a predefined field-of-view threshold, the system brakes and restores the wheelset to its longitudinal configuration. Finally, using the rail center at the braking moment and the fitted rail direction as references, a pure pursuit controller calculates pose and heading deviations, generates target linear and angular velocities, and closes the loop with the drive motor to achieve precise rail entry. Upon reaching the end of the rail, the robot halts and returns to the aisle, completing one inter-row operational cycle, as shown in Figure 8.
Figure 7. Schematic of the mobile robot’s lateral rail switching.
Figure 8. Workflow of lateral rail switching and inter-row navigation.
During the lateral translation phase, the onboard camera continuously captures rail images, and a YOLOv8n-based object detector is employed for real-time identification and localization of the rail center point, as shown in Figure 9.
Figure 9. YOLOv8n-based detection of the rail center point. (ad) present the training results obtained under different experimental scenarios.
The proposed mechanism combines deep vision-based detection with dynamic motion control. By maintaining high-accuracy rail recognition and precise entry localization, it significantly improves the flexibility and efficiency of cross-ridge rail-switching maneuvers, offering a practical and engineering-ready solution for autonomous operation in complex greenhouse environments.

3. Results

3.1. Evaluation of Global Mapping Accuracy in the Intralogistics Area

Using a remote client, the robot was teleoperated to traverse the multi-span greenhouse, and an environmental map was constructed using solid-state LiDAR in conjunction with LIO-SAM, as shown in Figure 10. A prior map with higher resolution and more clearly delineated structural details provides stronger support for accurate localization and navigation. The optimized LIO-SAM maps clearly delineate crop-row boundaries without noticeable distortion and provide extended coverage, faithfully capturing the structure and layout of the multi-span greenhouse.
Figure 10. Comparison of greenhouse maps generated by LIO-SAM: (a) Baseline LIO-SAM greenhouse map; (b) Optimized LIO-SAM greenhouse map. Positions 1 through 5 denote different measurement positions: Position 1 corresponds to a spacing of 13 rows, Position 2 to 1 row, Position 3 to 3 rows, Position 4 to 5 rows, and Position 5 indicates the width of the hardened pavement.
For evaluation, on-site ground-truth measurements were obtained with a measuring tape for cultivation-support height, support width, inter-ridge spacing, and the width of the hardened aisle. Measurement locations were sequentially labeled Positions 1 through 5. The corresponding map values at these positions were extracted using Rviz, a visualization tool in the Robot Operating System (ROS), and subsequently compared with the manual measurements []. Mapping accuracy was evaluated using absolute error, relative error, and root-mean-square error (RMSE). The results are summarized in Table 2.
Table 2. Accuracy analysis of the cultivation-area map.
We quantitatively evaluated mapping accuracy for inter-row spacing in multi-span greenhouse cultivation areas. With the unmodified pipeline, measurements of hardened-aisle width and inter-row spacing exhibited an absolute error of 6.3 cm and a relative error of 2%, alongside localized accuracy fluctuations. After applying the proposed glass-greenhouse optimizations, the absolute error decreased to 5.3 cm and the relative error to 1.7%. The average relative error decreased by approximately 15%, and the error distribution became tighter. These results indicate that the optimized system satisfies the accuracy requirements of greenhouse autonomous navigation and improves consistency, confirming the effectiveness of the mapping refinements in enhancing both accuracy and robustness under complex agricultural conditions.

3.2. Evaluation of Navigation Accuracy in the Intralogistics Zone

To validate the navigation accuracy, lateral displacement and heading deviation were measured along a predefined trajectory with pose observations collected every 1.6 m. Coordinate grids (105 cm × 75 cm) were mounted at the front and rear along the robot’s longitudinal axis, and laser emitters were used to mark the pose. At each sampling point, the robot paused for 5 s while the laser-spot coordinates on the grids were recorded. These measurements were used to compute lateral offset and heading offset. Experiments were carried out at three navigation speeds (0.2, 0.4, and 0.6 m/s), with ten independent trials conducted for each speed. The statistical results corresponding to different speeds are summarized in Table 3.
Table 3. Navigation deviation of the mobile robot.
The control performance of the robot at varying speeds can be evaluated using the normalized performance indicator ρ , as proposed by Mattila et al. []. This indicator is defined as follows:
ρ = m a x ( | X d e s X | ) m a x ( | X ˙ | ) = | e | m a x | X ˙ | m a x
where X d e s represents the desired position and X the measured position. Smaller values of ρ indicate superior tracking performance. The rationale for adopting this metric is that higher task-space velocities are typically accompanied by larger accelerations, which tend to exacerbate position-tracking errors.
The results show a monotonic increase in positional error with operating speed: both the mean and root-mean-square error (RMSE) of lateral displacement and heading deviation increase as velocity rises. This trend is more pronounced above 0.4 m/s. At 0.6 m/s, the mean lateral deviation exceeds that at 0.4 m/s by 6.75 cm, and the maximum lateral deviation increases markedly to 17.3 cm. Overall, the lateral deviation averages 11.76 cm (SD 2.69 cm), while the heading deviation averages 3.55° (SD 1.41°). Furthermore, employing the normalized performance indicator ρ provides a clear and quantitative assessment of the robot’s control performance.

3.3. Evaluation of Autonomous Rail-Switching Accuracy in the Cultivation Area

This section evaluates the dynamic performance of the proposed visual-navigation rail-switching control strategy under inter-row operating conditions in the cultivation area. Experiments were performed at three constant velocities (0.2, 0.4, and 0.6 m/s) to assess the rail-switching success rate. In parallel, the rail-switching time was compared with that of a conventional whole-vehicle steering approach. The evaluation verifies the feasibility of the proposed method and provides an empirical basis for parameter optimization of the lateral-motion control strategy. The results are summarized in Table 4.
Table 4. Autonomous rail switching evaluation in the cultivation area.
At speeds of 0.2, 0.4, and 0.6 m/s, the proposed visual-guided rail-switching method achieved success rates of 97%, 90%, and 73%, respectively, showing a monotonic decline with increasing speed. Compared with the conventional “turn-around and re-align” strategy, our approach is grounded in rail-center and heading-vector detection and closed-loop pose feedback, which enables direct lateral insertion into the adjacent rail and delivers an average 25.2% improvement in switching efficiency at 0.2 m/s.

4. Discussion

In maps constructed with the optimized LIO-SAM pipeline, the geometric boundaries between crop rows are sharply delineated with no appreciable positional distortion (Figure 10). The maps also exhibit extended spatial coverage, capturing the principal structural elements and spatial organization of the multi-span greenhouse. In highly repetitive greenhouse structures, the optimized LIO-SAM demonstrates enhanced robustness and environmental adaptability. Compared with 2D mapping methods, 3D LiDAR SLAM point-cloud maps offer higher spatial resolution and richer detail, enabling precise estimates of inter-row spacing, trellis height, obstacle volumes, and clearances. These properties yield a more reliable environmental representation to support path planning, obstacle avoidance, and operational decision-making in complex agricultural tasks.
At higher speeds, larger inter-sample pose variation combined with bias-estimation latency leads to short-term localization drift (Table 3). Moreover, actuator-wheel interactions amplify residual orientation errors, further reducing navigation accuracy. Despite the increase in error at higher speed, the system maintains high localization reliability in greenhouse environments, and its accuracy remains sufficient for low-speed operational tasks.
The degradation in localization accuracy arises primarily from the shorter dwell time of the rail endpoint within the camera’s field of view at higher speeds, which induces YOLOv8n detection latency or misses (Table 4). The associated reduction in detected rail-center samples undermines straight-line fitting of the rail heading, thereby inflating localization error. Furthermore, the combined effect of longitudinal inertia and lateral translation during execution amplifies lateral deviation, ultimately reducing entry accuracy.
Overall, the proposed vision-servo rail-switching strategy achieves high success rates and efficiency under low-speed conditions, making it well suited for autonomous greenhouse tasks such as harvesting, inspection, and crop protection. At higher speeds, however, its performance is limited by compounded detection latency, localization drift, and execution-induced deviations, emphasizing the need for further improvements in perception fidelity and control design. Nevertheless, the method substantially enhances inter-row traversal and cross-rail maneuverability, providing a strong foundation for greenhouse automation and operational efficiency.
Future research will focus on improving perception accuracy in high-speed scenarios, where multi-modal sensing approaches (e.g., LiDAR, stereo vision, and depth cameras) may help mitigate detection delays and localization drift. The integration of advanced control strategies, such as adaptive and model predictive control, could further improve maneuverability under dynamic uncertainties. Extending the framework to cooperative multi-robot systems would enable task allocation, coordinated navigation, and information sharing, enhancing scalability for large-scale greenhouse operations. In addition, long-term field trials across different crop types, seasonal conditions, and greenhouse layouts will be essential to validate robustness and generalizability. These directions point toward advancing the intelligence, adaptability, and efficiency of autonomous greenhouse operations.

5. Conclusions

This study addressed the challenges of autonomous operation in multi-span glass greenhouses by proposing an integrated localization-navigation framework that accommodates the structural complexity and operational demands of both intralogistics and cultivation areas. At the hardware level, the drive and steering wheelsets were optimized to enable a high-efficiency lateral rail-switching mechanism, and a Controller Area Network (CAN)-based distributed control architecture was incorporated to support reliable operation across heterogeneous greenhouse scenarios.
To overcome the susceptibility of solid-state LiDAR to reflective artifacts in glass environments, we introduced a series of LIO-SAM optimizations, including reflection-intensity filtering, adaptive feature-extraction thresholds, and enhanced loop-closure detection. These refinements reduced the mean relative mapping error by 15%. Within the navigation stack, an A-Star global planner and DWA local obstacle avoidance were integrated with AMCL-based pose correction, achieving a lateral localization error of 6.01 cm and a heading error of 2.56° at 0.4 m/s, thereby meeting the requirements for autonomous mobility in intralogistics operations.
In the cultivation area, where interlaced rails and internal corridors complicate navigation, a coordinated scheme coupling lateral wheelset steering with YOLOv8n-based rail detection was developed to achieve cross-ridge switching without reorienting the entire vehicle. At speeds below 0.4 m/s, the maximum lateral error was limited to 12 cm and the heading error to 6°. With pure-pursuit-based visual-servo control, rail-switching efficiency improved by 25.2% at 0.2 m/s. Furthermore, the markerless design reduces manual maintenance costs, underscoring its practical engineering value.
Through platform-level integration and field validation, the proposed system demonstrated strong performance in localization accuracy, rail-switching efficiency, and navigation robustness. Future work will explore dynamic obstacle avoidance, cooperative multi-robot path planning, and broader deployment in large-scale greenhouses, thereby advancing the intelligence, adaptability, and efficiency of facility-agriculture operations.

Author Contributions

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

Funding

This research was supported by the Suzhou Science and Technology Program (SNG2022055) and the Science and Technology Project of Jiangsu Province Administration for Market Regulation under Grant (KJ2024079).

Data Availability Statement

Dataset available on request from the authors.

Acknowledgments

During the preparation of this manuscript, the authors used ChatGPT-5 to assist with grammar correction and format adjustment. The authors have reviewed and edited the output and take full responsibility for the content of this publication.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
GNSSGlobal Navigation Satellite System
SLAMSimultaneous Localization and Mapping
LIO-SAMLiDAR Inertial Odometry via Smoothing and Mapping
LIDARLight Detection and Ranging
IMUInertial Measurement Unit
DWADynamic Window Approach
AMCLAdaptive Monte Carlo Localization
YOLOYou Only Look Once
RVIZRobot Visualization

References

  1. Chen, Y.; Bao, A.; Li, Y.; Xiang, Y.; Cai, W.; Xia, Z. A novel multi-source data-driven energy consumption prediction model for Venlo-type greenhouses in China. Smart Agric. Technol. 2025, 10, 100825. [Google Scholar] [CrossRef]
  2. Hutsol, T.; Kutyrev, A.; Kiktev, N.; Biliuk, M. Robotic Technologies in Horticulture: Analysis and Implementation Prospects. Agric. Eng. 2023, 27, 113–133. [Google Scholar] [CrossRef]
  3. Lakhiar, I.A.; Yan, H.; Syed, T.N.; Zhang, C.; Shaikh, S.A.; Rakibuzzaman, M.; Vistro, R.B. Soilless Agricultural Systems: Opportunities, Challenges, and Applications for Enhancing Horticultural Resilience to Climate Change and Urbanization. Horticulturae 2025, 11, 568. [Google Scholar] [CrossRef]
  4. He, Y.; Huang, Z.; Yang, N.; Li, X.; Wang, Y.; Feng, X. Research Progress and Prospects of Key Navigation Technologies for Facility Agriculture Robots. Smart Agric. 2024, 6, 1–19. [Google Scholar] [CrossRef]
  5. Arad, B.; Balendonck, J.; Barth, R.; Ben-Shahar, O.; Edan, Y. Development of a sweet pepper harvesting robot. J. Field Robot. 2020, 37, 1027–1039. [Google Scholar] [CrossRef]
  6. Hua, W.; Zhang, Z.; Zhang, W.; Liu, X.; Hu, C.; He, Y. Key technologies in apple harvesting robot for standardized orchards: A comprehensive review of innovations, challenges, and future directions. Comput. Electron. Agric. 2025, 235, 110343. [Google Scholar] [CrossRef]
  7. Singh, N.; Tewari, V.K.; Biswas, P.K.; Dhruw, L.K.; Hota, S.; Mahore, V. In-field performance evaluation of robotic arm developed for harvesting cotton bolls. Comput. Electron. Agric. 2024, 227, 109517. [Google Scholar] [CrossRef]
  8. Abanay, A.; Masmoudi, L.; Benkhedra, D.; Amraoui, K.E.; Lghoul, M.; Jimenez, J.; Moreno, F. A transformation model for vision-based navigation of agricultural robots. Cogn. Robot. 2025, 5, 140–151. [Google Scholar] [CrossRef]
  9. Wang, Y.; Fu, C.; Huang, R.; Tong, K.; He, Y.; Xu, L. Path planning for mobile robots in greenhouse orchards based on improved A* and fuzzy DWA algorithms. Comput. Electron. Agric. 2024, 2, 227. [Google Scholar] [CrossRef]
  10. Tan, H.; Zhao, X.; Fu, H.; Yang, M.; Zhai, C. A novel fusion positioning navigation system for greenhouse strawberry spraying robot using LiDAR and ultrasonic tags. Agric. Commun. 2025, 3, 100087. [Google Scholar] [CrossRef]
  11. Li, M.; Zhu, X.; Ji, J.; Jin, X.; Li, B.; Chen, K.; Zhang, W. Visual perception enabled agriculture intelligence: A selective seedling picking transplanting robot. Comput. Electron. Agric. 2025, 229, 109821. [Google Scholar] [CrossRef]
  12. Qi, Z.; Zhang, W.; Yuan, T.; Rong, J.; Hua, W. An improved framework based on tracking-by-detection for simultaneous estimation of yield and maturity level in cherry tomatoes. Measurement 2024, 226, 114117. [Google Scholar] [CrossRef]
  13. Yuan, M.; Wang, D.; Lin, J.; Yang, S.; Ning, J. SSP-MambaNet: An automated system for detection and counting of missing seedlings in glass greenhouse-grown virus-free strawberry. Plant Phenomics 2025, 7, 100043. [Google Scholar] [CrossRef]
  14. Qi, F.; Li, K.; Li, S.; He, F.; Zhou, X. Research on the Implications of the Development of Intelligent Equipment for Protected Horticulture Worldwide for China. Trans. Chin. Soc. Agric. Eng. 2023, 43, 87. [Google Scholar] [CrossRef]
  15. Guo, Z.; Zhang, Y.; Xiao, H.; Jayan, H.; Majeed, U. Multi-sensor fusion and deep learning for batch monitoring and real-time warning of apple spoilage. Food Control. 2025, 172, 111174. [Google Scholar] [CrossRef]
  16. Jiang, J.; Zhang, T.; Li, K. LiDAR-based 3D SLAM for autonomous navigation in stacked cage farming houses: An evaluation. Comput. Electron. Agric. 2025, 230, 109885. [Google Scholar] [CrossRef]
  17. Pan, Y.; Hu, K.; Cao, H.; Kang, H.; Wang, X. A novel perception and semantic mapping method for robot autonomy in orchards. Comput. Electron. Agric. 2024, 219, 108769. [Google Scholar] [CrossRef]
  18. Kutyrev, A.; Kiktev, N.; Jewiarz, M.; Khort, D.; Smirnov, I.; Zubina, V.; Hutsol, T.; Tomasik, M.; Biliuk, M. Robotic Platform for Horticulture: Assessment Methodology and Increasing the Level of Autonomy. Sensors 2022, 22, 8901. [Google Scholar] [CrossRef]
  19. Tsiakas, K.; Papadimitriou, A.; Pechlivani, E.M.; Giakoumis, D.; Frangakis, N.; Gasteratos, A.; Tzovaras, D. An Autonomous Navigation Framework for Holonomic Mobile Robots in Confined Agricultural Environments. Robotics 2023, 12, 146. [Google Scholar] [CrossRef]
  20. Gupta, S.K.; Yadav, S.K.; Soni, S.K.; Shanker, U.; Singh, P.K. Multiclass weed identification using semantic segmentation: An automated approach for precision agriculture. Ecol. Inform. 2023, 78, 102366. [Google Scholar] [CrossRef]
  21. Saati, T.; Albitar, C.; Jafar, A. An Improved Path Planning Algorithm for Indoor Mobile Robots in Partially-Known Environments. Autom. Control Comput. 2023, 57, 1–13. [Google Scholar] [CrossRef]
  22. Shan, T.; Englot, B.; Meyers, D.; Wang, W.; Ratti, C.; Rus, D. LIO-SAM: Tightly-coupled Lidar Inertial Odometry via Smoothing and Mapping. 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]
  23. Fan, Z.; Liu, S. An improved YOLOv8n Algorithm and its Application to Autonomous Driving Target Detection. In Proceedings of the 2024 IEEE 6th International Conference on Power, Intelligent Computing and Systems (ICPICS), Shenyang, China, 26–28 July 2024. [Google Scholar] [CrossRef]
  24. Li, C.; Peng, C.; Zhang, Z.; Miao, Y.; Zhang, M.; Li, H. Localization and Mapping Method for Agricultural Robots Fusing Odometry Information. Trans. Chin. Soc. Agric. Eng. (Trans. CSAE) 2021, 37, 16–23. [Google Scholar] [CrossRef]
  25. Mattila, J.; Koivumäki, J.; Caldwell, D.; Semini, C. A Survey on Control of Hydraulic Robotic Manipulators with Projection to Future Trends. IEEE/ASME Trans. Mechatron. 2017, 22, 669–680. [Google Scholar] [CrossRef]
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.

Article Metrics

Citations

Article Access Statistics

Article metric data becomes available approximately 24 hours after publication online.