ROS and ROS2 Navigation Stacks: A performance review

Gaurav Gupta
March 1, 2023
Read time 7 mins

ROS1 (henceforth referred to as ROS) navigation stack has been the go-to place for students, robotics enthusiasts, and oftentimes companies in their early stage of development. ROS navigation stack (NavStack) comes with extensive documentation, a guide to setup transforms, sensor-related checks, and perhaps most importantly — implementations of SLAM, pure localization, global and local planning algorithms.

Even though the ROS NavStack is far from sufficient when it comes to deploying robots for industrial settings, it is a fairly common practice to follow the “use what you like” approach from the navigation stack. The release of ROS2 also brought about the roll-out of the Nav2Stack. Working as a robotics consultant, I am often asked about what’s new with ROS2 navigation stack or if it is the right time to switch to ROS2. Selection of ROS or ROS2 for robot application is contingent on several considerations, at the same time out of the box navigation performance is likely to contribute to the decision making of certain businesses and use-cases. While there are several differences between the two navigation releases, the limited purpose of this article is the experimental evaluation of out-of-the-box performances of default mapping, pure localization, global planning, and local planning across the two releases. My team at Black Coffee Robotics conducted several experiments to qualitatively compare the performances of default algorithms in these stacks and I present our findings here. Our focus was to evaluate the two stacks on the following test cases -

  1. SLAM: Large indoor complexes
  2. Global Planning: Quality of paths and computation time
  3. Local Planning: Ability to get past unknown obstacles

The robot and the environment

We designed a large factory-like Gazebo world (10000 sq.m!). Our goal was to create an environment large enough to pose a challenging SLAM problem. Autonomous Mobile Robots (AMRs) are often deployed in large factory floors and warehouses. These places present several challenges to robots — mapping large spaces isn’t always trivial, re-localization is a harder problem because of dynamic environments and possible symmetries in the arena. Given the collaborative and imperfect nature of humans and other objects in the environment, there are challenges around the corner for global/local planners too.

Gazebo model of a large factory floor

We simulated Blackbot, a differential drive mobile robot for our experiments. The robot was mounted with 2D Lidar of 30m range, 360-degree FoV, and 0.5-degree angular resolution.

Blackbot: Differential drive robot platform

GMapping (SLAM — ROS NavStack)

ROS uses gmapping package, a particle filter based SLAM solution for mobile robots. We used default parameters to observe the mapping performance.

The performance of gmapping on our simulated world was surprisingly impressive. We were able to generate the map online without any tuning. This to some extent was a slight deviation from our on-field experiences in large environments. Our past experience has involved bag recording and offline parameter tuning to get loop closures with gmapping.

SLAM Toolbox

SLAM Toolbox comes with an extensive feature list including relocalization, continued mapping, and long-term mapping and map merging. For this comparison, we restrict our focus to SLAM. slam_toolbox is a pose graph SLAM approach that utilizes karto scan matcher. The package claims to be particularly useful for large indoor environments — our target use case. Here’s how it went-

While the package delivers on its claim of mapping large spaces, saving the map itself using the map_server ROS2 package wasn’t a smooth process (issue here). SLAM Toolbox is a promising step towards a reliable SLAM solution but we’ll have to wait and see when enough experience is gathered around real world settings.

NavFn (Global Planner — NavStack)

NavFn uses Djikstra’s planner to plan the shortest path from start to goal. Other than exploring A* planning with heuristics as an option, NavFn provides little flexibility in controlling what kind of global plan is generated — it will generate the shortest cost path (cost determined by costmap) but does not account for smoothness of path, number of turns involved, constraints like the radius of curvature, etc. As experience proves — simplicity has its own advantages.

NavFn Global Plan, time taken: 2.4 seconds

SMAC Planner (Global Planner — Nav2Stack)

SMAC planner is one of the two planning servers shipped with Nav2Stack — the other being NavFn itself. SMAC planner implements Hybrid State A*, this algorithm allows continuous state transitions in discrete navigation cells and also gives the option to select the motion model (such as DUBIN, 2D Moore, etc). There are several other parameters pertaining to optimization, down-sampling, and cost multipliers. All these parameters provide flexibility in altering the behavior of the planner as per application.

SMAC Planner, time taken: 1.2 seconds

The path shown in red is a result of SMAC planner. While we didn’t change the default parameters provided by the planner, the global path seems to be hugging the obstacles along the horizontal axis. It’s hard for us to see an obvious circumstance where this would be desirable but this is a subject of further exploration.

Trajectory Rollout Planner (Local Planner — NavStack)

ROS NavStack comes with the trajectory rollout planner and Dynamic Window Approach (DWA). Both planners work on the principle of discrete sampling of robot’s control inputs within user-specified constraints, evaluation of resulting trajectories based on appropriate costs, and selection of best-performing inputs. We performed multiple simulations without parameter tuning for trajectory rollout planner (but appropriate robot footprint), results were unfortunately disappointing. In our past experience with hardware deployment, we have observed better results (but far from perfect) with DWA and TEB local planners.

DWB Planner (Local Planner — Nav2Stack)

Nav2Stack comes with the implementation of DWB planner — an implementation successor to DWA planner. As per the available documentation, there hasn’t been a lot of change in terms of core algorithm but there have been software upgrades targeting bug fixes and customization of code. We ran NavStack and Nav2Stack under similar (if not identical) circumstances, our goal was to analyze their performance in the face of static but unknown obstacles, and congested moving spaces. For most runs DWB allowed the robot to circumnavigate obstacles, however, one run, in particular, was anomalous where the robot crashed into an obstacle.

Conclusion

ROS NavStack is heavily utilized by students, hobbyists, and in factions of industries. The rich documentation and community support make the process of setting up a robot with NavStack seamless. In our experience, ROS2 falls short when it comes to documentation (which is understandable). Setting up launch files in python with relatively little documentation, and new concepts such as lifecycle management, QoS settings can prove to be overwhelming.

On the algorithm front, it does seem that major bugs have been fixed, particularly with local planning. There are several parameters pertaining to the SLAM toolbox, SMAC planner, and DWB planner that we haven’t explored as part of this study but will be the subject of future work. Readers can check out the full set of videos here.

Are you a robotics business looking to build navigation system for your autonomous robots? Let’s get in touch!

Read more
Careers
| Copyright © 2023 Black Coffee Robotics