1. Introduction
Omnidirectional mobile robots can move in any direction without needing to rotate their chassis, offering superior maneuverability in constrained environments. One common approach to achieve omnidirectional motion is the use of Mecanum wheels—wheels fitted with angled rollers that translate wheel rotation into lateral movement components [
1,
2,
3]. Robots equipped with four Mecanum wheels can control motion in the plane
X–
Y and rotation about the yaw axis, enabling holonomic motion capabilities.
Simulation of omnidirectional mobile robots with Mecanum wheels has become a fundamental tool in the design and validation of navigation and control algorithms before real-world deployment. Several simulation frameworks exist within the ROS ecosystem, with Gazebo standing out for its flexibility and integration with ROS middleware. However, simulating realistic omnidirectional robot behavior—especially for platforms with Mecanum wheels—poses significant challenges due to the complex interaction between wheels and the ground, as well as high sensitivity to model parameters. Existing plugins such as the
gazebo_planar_move_plugin plugin or more specialized omnidirectional drive plugins [
4,
5,
6] provide basic functionality, but often lack precise interfaces to control individual wheel speeds.
Visual-based navigation using fiducial markers such as AprilTags has been widely studied for indoor autonomous mobile robots [
7,
8,
9]. These tags serve as robust landmarks for localization, mapping, and path correction. Mapping strategies based on AprilTag detection have been employed for SLAM and global localization [
10,
11], often enhanced through optimization techniques or probabilistic filtering. Furthermore, local path planning methods leveraging A* algorithms continue to be a preferred choice due to their deterministic nature and computational efficiency [
12]. Integration of global and local planning with dynamic obstacle avoidance has also been explored in modular ROS architectures. However, despite the robustness of these components individually, few simulation environments accurately integrate realistic robot dynamics, AprilTag-based navigation, and modular planning and control pipelines under noisy and uncertain conditions.
It is worth mentioning that this work does not take into consideration the robot’s relocalization or simultaneous localization and mapping tools, which will be addressed in future efforts. Despite the robustness of traditional methods such as A* and cubic B-spline smoothing, few works integrate them with realistic Mecanum dynamics, AprilTag-based navigation, and multiple trajectory controllers under noisy conditions, which constitutes the main novelty of this framework.
The main contributions of this paper are as follows: (i) the development of a realistic simulation framework in Gazebo/ROS for omnidirectional robots with Mecanum wheels, including detailed wheel–ground interaction modeling; (ii) the integration of AprilTag-based visual navigation to construct occupancy grids as a cost-effective alternative to LiDAR, supporting robust mapping and path correction; (iii) a modular planning and control architecture that allows interchangeable use of trajectory planners (such as A*) and trajectory-following controllers (Lyapunov, null-space Lyapunov, and PI); and (iv) extensive validation through simulation experiments in maze-like environments under noise and uncertainty, demonstrating robustness of the integrated pipeline. The remainder of this paper presents the methodology, experimental results, discussion, and conclusions.
2. Methodology
The proposed navigation architecture is designed to enable smooth, responsive, and visually guided motion in omnidirectional mobile robots. It consists of two complementary path planning modules: a global and a local planner, that allow reactive autonomous navigation with time-parameterized trajectories. We rely on a B-spline smoothing scheme for the computed trajectories to ensure soft maneuvers. The following sections bring details about the mentioned components.
2.1. Offline Visual Mapping
The offline visual mapping stage comprises a sequence of interconnected nodes designed to detect visual obstacles, update a global occupancy grid, and provide manual teleoperation capabilities for data acquisition.
Figure 1 describes the overall workflow, from raw image acquisition to the generation of the static global map used by the global planner. Each block in this diagram corresponds to a specific processing node, which is described in detail in the following paragraphs.
2.2. Visual Obstacle Detection Node
The first stage of the mapping system is carried out in a simulated environment using the Gazebo simulator. An omnidirectional robot equipped with a monocular camera plugin navigates through a maze populated with fiducial tags (AprilTags), which act as visual obstacles. The camera captures real-time images of the environment, which are fed to a detection node responsible for identifying and localizing these markers, as illustrated in the lower left corner of
Figure 1.
The visual detection pipeline begins with intrinsic calibration to ensure geometric consistency in the projection of image points. AprilTag detection is then performed using OpenCV, which returns the 3D pose of each tag relative to the camera frame noted as . The resulting transform has rotational and translational components in 3D. Note that the Z-axis component will not be used.
To ensure reliable mapping, a filtering stage is applied to discard noisy or spurious detections. A tag observation is only accepted if the following conditions are simultaneously satisfied: (i) the robot is stationary or almost stopped, determined by monitoring the velocities of the wheels and comparing them to a small threshold ≤0.5 rad/s; (ii) the distance between the robot and the tag is ≤1.5 m; and (iii) the same tag has been observed multiple consecutive times, indicating temporal stability.
Once validated, the tag pose is transformed from the camera frame
to the global map frame
using the following SE(3) transformation chain:
where the transform from the robot to the global frame
is computed using odometry. Note that
is a fixed transform from the camera frame to the robot frame based on the sensor disposition. It is worth mentioning that we assume a constant
Z value for all tags, and we used only the
components to build the occupancy grid.
2.3. Mapping Node
The mapping node is responsible for updating a two-dimensional occupancy grid with the estimated positions of obstacles. Each fiducial marker is projected as a rectangular region centered at its global location. The dimensions of this region are fixed at 0.15 m in length and 0.05 m in width, corresponding to the approximate tag of the visual obstacle. The environment is discretized into a 2D grid, where each cell represents the occupancy state of a specific area of the map. Initially, all cells are marked as free. As new detections are received, the corresponding grid regions are updated and set to an occupied value. The mapping is performed incrementally and accumulates information over time, enabling the construction of the environment based solely on visual input.
To ensure the consistency and accuracy of the 2D occupancy map, a remapping algorithm is implemented to update previously mapped AprilTags when new detections suggest a significantly different spatial configuration. Remapping occurs if the robot’s orientation changes by more than , or if the Euclidean distance to the tag differs by m or more compared to the prior mapping instance. Additionally, the global position of the tag is recomputed and compared against its stored location. If the discrepancy exceeds a defined threshold, the occupancy map is updated by repositioning the associated rectangle in the new estimated location. The resulting occupancy grid is exported as a static global map file, which serves as the input for the global planner.
Manual Control Node
During the mapping stage, the robot is operated remotely using a wireless Bluetooth joystick whose inputs are interpreted as desired linear forward/backward velocities
and lateral velocities
, as well as angular rotations around the
Z axis. The robot’s direct and inverse kinematics that allow handling the system’s velocities are expressed as:
where
r is the wheel radius,
is the longitudinal distance from the robot’s center to each wheel,
is the lateral distance, and
are the angular velocities of the wheels. This ensures that the omnidirectional motion commanded by the operator is accurately translated into coordinated wheel movements.
2.4. Global Trajectory Planning
The global planning subsystem shown in
Figure 2 requires a map loading and binarizationprocess to plan a suitable trajectory for the robot. The module reads an input image in
.png format that represents the layout of the environment. The image is first converted to grayscale, resulting in an intensity matrix
[0–255], where each pixel encodes a position in the environment (255 free space, 0 occupied space). The map file is converted into a binary matrix
named a occupancy grid, where each cell represents a discrete navigable or blocked location. The regions around obstacles contain a safety margin of
blocks per cell This prevents trajectories from being planned too close to narrow corridors or wall edges.
The resulting binary map is used to plan the robot’s global trajectory, the process of which requires the start and goal point in grid coordinates, yielding:
where
denotes the starting point and
the final point of the trajectory in the global frame.
are the minimum coordinate bounds of the map;
is the map resolution (meters per cell), and
is a point in the grid frame. Note that the Euclidean distance from the start to the goal must be larger than a threshold to avoid trivial short trajectories.
2.4.1. Trajectory Planning Algorithm
In this work we rely on the A* algorithm for finding the least-cost path on a weighted graph by combining the exact path cost from the start with a heuristic estimate of the cost to the goal [
13]. Here, the environment is represented as the binary occupancy grid provided by the global mapping node. Formally, given a directed graph
induced by the free cells of the grid and non-negative edge costs
, a start node
, and a goal node
, the algorithm assigns each vertex
a
cost-to-come , representing the best-known cost from
s to
v, and a heuristic cost-to-go
, representing an estimate of the optimal cost from
v to
t.
The evaluation function is defined as , which orders nodes in a priority queue (OPEN list) from which the next node to expand is selected. The algorithm initializes , for , and inserts s into the queue with key . At each step, it extracts from OPEN; if , the optimal path is reconstructed by backtracking predecessors . Otherwise, for each neighbor v of u, the tentative cost is computed as and if , the values , , and are updated, inserting v into OPEN if not already present. The choice of typically reflects the Euclidean or Manhattan distance between v and t in the grid. A heuristic h is admissible if for all v, where is the true minimal cost from v to t; it is consistent if for all . When h is admissible, A* guarantees an optimal solution; with consistency, the algorithm never needs to reopen nodes. The resulting path is post-processed using a B-spline smoothing technique to produce a continuous and dynamically feasible trajectory.
2.4.2. Trajectory Smoothing Algorithm
In the post-processing stage of both the global and local planners, a trajectory smoothing algorithm is applied to reduce abrupt directional changes and ensure continuity in both position and curvature, thereby facilitating more accurate controller tracking. The cubic spline method is a widely used technique for generating smooth trajectories through a set of
n given points [
14],
. The goal is to determine the second derivatives
at each point such that the spline is twice continuously differentiable. For natural splines,
and
. For
, the system to solve is
where
is the spacing between consecutive points along the independent variable. This leads to the tridiagonal system
with:
where
. The solution is obtained as
. Here,
are the known positions,
the segment lengths, and
the spline’s second derivatives at each knot. Recall that the global trajectory planner node and the local trajectory planner node apply this smoothing process. The smoothed trajectory is now passed as a trajectory message for either of the planner nodes.
2.5. Local Trajectory Planning
The local planner operates as a reactive navigation layer that complements the global trajectory. As illustrated in
Figure 2, the system continuously receives updated obstacle information from the visual detection module and triggers a short replanning whenever an AprilTag is detected at less than
from the robot. Let the robot pose be
and the pre-computed global path be
. A temporary goal
is chosen ahead of the robot, at least
away, within a forward viewing angle of
, and located in a free cell of the occupancy grid.
The local path is computed from to using the A* algorithm with the same formulation as in the global planner, but including an obstacle-proximity penalty to favor safer clearance. The resulting waypoints are refined by cubic B-spline smoothing with reduced tension, allowing tighter curvature radii for effective obstacle evasion.
To merge back into the global path, the last points of the smoothed local path when – are replaced by the corresponding waypoints of starting from index , defined as the closest forward waypoint to . When no new obstacles are detected within the safety radius, tracking resumes along from , restoring the replanning path with minimal deviation.
2.6. Trajectory Following Control
The trajectory following stage ensures that the robot accurately tracks the planned reference
by converting tracking errors into coordinated wheel commands according to the kinematic model in (
2). Three controllers were implemented for comparison: kinematic proportional, null-space, and PI. Note that the control actions for all controllers denoted with
,
, and
in the following subsections represent a
vector with the angular speed for each wheel required to position the robot according to a trajectory.
2.6.1. Kinematic Proportional Controller
The kinematic proportional controller minimizes the error between the robot’s estimated state
and the current reference
. The control action
is computed as a virtual acceleration proportional to the error
as
These accelerations are mapped into wheel angular velocities via the inverse Jacobian, yielding
, where
is the analytically derived inverse kinematic matrix of the Mecanum configuration stated in Equation (
2).
2.6.2. Null-Space Controller
The null-space controller extends the standard proportional law by introducing a secondary task for orientation control that is projected onto the null space of the main
x–
y tracking task. The reduced Jacobian for the
x–
y task is denoted
; let
. The
reduced Jacobian that maps wheel speeds to planar linear velocities is the first two rows of the full Jacobian in (
2) is (
5).
And the corresponding null-space projection matrix is
, yielding the control law:
where
is a proportional gain. The first term drives position tracking, while the second adjusts orientation without disturbing the primary task.
2.6.3. PI Controller
The PI controller also uses the inverse mapping from (
2) but augments the proportional term with an integral component to eliminate steady-state error as
where
is the integral gain matrix.
3. Results
To evaluate the proposed trajectory controllers, two 6 × 6 m maze-like environments were created in Gazebo using the same Python-based generation algorithm to ensure comparable complexity and obstacle density. AprilTags were placed on maze walls as visual landmarks for obstacle detection. The three controllers tested were (i) a Lyapunov-based proportional controller with gain , (ii) a null-space Lyapunov controller with orientation gain , and (iii) a PI controller with gains and .
The evaluation comprised two stages. In the offline mapping phase, the robot detected AprilTags and built an occupancy grid of the static environment, from which a global path was planned with A*. In the second phase, additional AprilTags simulated dynamic obstacles. When the front-facing monocular camera detected a new tag within 0.6 m, local replanning was triggered using A* on the updated map. The robot followed the local path until the obstacle cleared, then progressively rejoined the global path. Three controllers were tested in both mazes under identical trajectories and replanning strategies, recording position tracking errors and control effort for performance metrics.
Figure 3 shows the navigation results in two test environments: (a) Maze A and (b) Maze B. The red curve is the initial global path, the green curve is the locally replanned path triggered by AprilTag-based detection of unmapped obstacles, and the black curve is the robot’s actual trajectory. Blue rectangles mark dynamically detected AprilTags absent from the initial occupancy map. The results demonstrate the robot’s ability to avoid unforeseen obstacles and rejoin the original path, validating the integration of local planning with visual perception.
Figure 4 summarizes the experiments in both mazes with three trajectory-tracking controllers: (a) Gazebo setup for Maze A/B with JetAuto following the reference; (b) RViz overlays the robot’s estimated pose and trajectory on the AprilTag-based occupancy grid; (c) comparison of the reference trajectories and the actual robot trajectories. The apparent deviations from the global path occurred when the robot performed local replanning upon detecting new obstacles. In these cases, the controllers correctly followed the local reference, allowing the robot to bypass obstacles safely before rejoining the global path.
Table 1 shows that NS-Lyap consistently achieved the best tracking in both mazes, yielding the lowest ISE, RMSE, and maximum deviation, and remaining accurate even during local replanning triggered by obstacle detections. By contrast, the PI controller produced the largest positional errors and the highest peak deviations, although it required the least control effort with lowest MTE. The standard Lyapunov controller was intermediate, balancing accuracy and command smoothness.
4. Conclusions
This work presented a complete simulation framework for autonomous navigation of an omnidirectional mobile robot using AprilTags as visual landmarks, integrating high-fidelity modeling, global and local planning, trajectory smoothing, and trajectory tracking controllers within the ROS and Gazebo environment. The proposed system addresses the challenges of navigation in dynamic environments by combining an offline mapping stage with global planning based on the A* algorithm, and an online local replanning strategy triggered by real-time detection of previously unmapped obstacles. The incorporation of morphological dilation in the occupancy grid generation proved essential for increasing path safety margins, while the trajectory smoothing stage—implemented via collinearity reduction and cubic B-splines—ensured continuous, dynamically feasible paths for the controller. Simulation results in two maze-like environments validated the ability of the system to detect and avoid dynamic obstacles, rejoin the global path, and maintain high tracking precision despite trajectory deviations. This confirms the robustness of the integrated planning–perception–control pipeline under uncertainty and noise conditions.
Future work will focus on extending the validation to real-world platforms, incorporating additional perception modalities such as LiDAR or depth cameras, and exploring adaptive control strategies to further enhance robustness in highly dynamic and unstructured environments.
Author Contributions
Conceptualization, W.C. and B.S.H.; methodology, W.C.; software, B.S.H.; validation, M.G.; investigation, B.S.H.; resources, W.C.; data curation, D.M.; writing—original draft preparation, W.C.; writing—review and editing, D.M.; visualization, W.C. All authors have read and agreed to the published version of the manuscript.
Funding
This research received no external funding.
Institutional Review Board Statement
Not applicable.
Informed Consent Statement
Not applicable.
Data Availability Statement
Contact the authors for data availability.
Conflicts of Interest
The authors declare no conflicts of interest.
References
- Doroftei, I.; Grosu, V.; Spinu, V. Omnidirectional mobile robot–design and implementation. In Bioinspiration and Robotics: Walking and Climbing Robots; Habib, M.K., Ed.; InTech: London, UK, 2007; pp. 511–528. [Google Scholar]
- Adăscăliţei, F.; Doroftei, I. Practical applications for mobile robots based on Mecanum wheels—A systematic survey. In Proceedings of the 3rd International Conference on Innovations, Recent Trends and Challenges in Mechatronics, Mechanical Engineering and New High-Tech Products Development (MECAHITECH), Bucharest, Romania, 22–23 September 2011; pp. 112–123. [Google Scholar]
- Patruno, C.; Renò, V.; Nitti, M.; Mosca, N.; di Summa, M.; Stella, E. Vision-based omnidirectional indoor robots for autonomous navigation and localization in manufacturing industry. Heliyon 2024, 10, e26042. [Google Scholar] [CrossRef] [PubMed]
- Apurin, A.; Smagin, N.; Smagin, A. Omniwheel Chassis’ Model and Plugin for Gazebo Simulator. In Proceedings of the 2023 International Conference on Industrial Engineering, Applications and Manufacturing (ICIEAM), Sochi, Russia, 15–19 May 2023. [Google Scholar]
- Koenig, S.; Likhachev, M. Fast replanning for navigation in unknown terrain. IEEE Trans. Robot. 2005, 21, 354–363. [Google Scholar] [CrossRef]
- Paz, E.; Sebastian, J.M.; Armada, M.A.; de Santos, P.G. Hybrid Modular Architecture for Control of Mecanum-Wheeled Robots. IEEE Access 2021, 9, 92543–92553. [Google Scholar]
- Olson, E. AprilTag: A robust and flexible visual fiducial system. In Proceedings of the IEEE International Conference on Robotics and Automation (ICRA), Shanghai, China, 9–13 May 2011; pp. 3400–3407. [Google Scholar] [CrossRef]
- Huang, Y.; Lin, C. Indoor Localization Method for a Mobile Robot Based on Dual AprilTag Fiducials and AMCL. Sensors 2023, 23, 3792. [Google Scholar]
- Hijikata, M.; Watanabe, S.; Osada, T.; Tani, K. Wheel Arrangement of Four Omni Wheel Mobile Robot Considering Usefulness of Space. In Proceedings of the 2022 61st Annual Conference of the Society of Instrument and Control Engineers of Japan (SICE), Kumamoto, Japan, 6–9 September 2022; pp. 1070–1075. [Google Scholar]
- Wu, M.; He, Z.; Gao, S. Mixed Reality Enhanced User Interactive Path Planning for Omnidirectional Robots. Appl. Sci. 2020, 10, 1135. [Google Scholar] [CrossRef]
- Piemngam, K.; Ueno, W.; Sampei, M. Development of Autonomous Mobile Robot with Optimal Trajectory Planning Based on Visual Information. In Proceedings of the 2019 International Conference on Advanced Science and Engineering (ICOASE), Zakho-Duhok, Iraq, 2–4 April 2019; pp. 337–342. [Google Scholar]
- Hart, P.E.; Nilsson, N.J.; Raphael, B. A Formal Basis for the Heuristic Determination of Minimum Cost Paths. IEEE Trans. Syst. Sci. Cybern. 1968, 4, 100–107. [Google Scholar] [CrossRef]
- Gasparetto, A.; Boscariol, P.; Lanzutti, A.; Vidoni, R. Path planning and trajectory planning algorithms: A general overview. In Motion and Operation Planning of Robotic Systems: Background and Practical Approaches; Springer: Berlin/Heidelberg, Germany, 2015; pp. 3–27. [Google Scholar]
- Ferguson, D.; Stentz, A. Using interpolation to improve path planning: The Field D* algorithm. J. Field Robot. 2006, 23, 79–101. [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. |
© 2025 by the authors. Licensee MDPI, Basel, Switzerland. This article is an open access article distributed under the terms and conditions of the Creative Commons Attribution (CC BY) license (https://creativecommons.org/licenses/by/4.0/).