Next Article in Journal
PAR-Net: An Enhanced Dual-Stream CNN–ESN Architecture for Human Physical Activity Recognition
Next Article in Special Issue
Learning-Based Hierarchical Decision-Making Framework for Automatic Driving in Incompletely Connected Traffic Scenarios
Previous Article in Journal
PixRevive: Latent Feature Diffusion Model for Compressed Video Quality Enhancement
Previous Article in Special Issue
Multi-Object Trajectory Prediction Based on Lane Information and Generative Adversarial Network
 
 
Font Type:
Arial Georgia Verdana
Font Size:
Aa Aa Aa
Line Spacing:
Column Width:
Background:
Review

A Review on Traversability Risk Assessments for Autonomous Ground Vehicles: Methods and Metrics

by
Mohamed Benrabah
*,
Charifou Orou Mousse
,
Elie Randriamiarintsoa
,
Roland Chapuis
and
Romuald Aufrère
Clermont Auvergne INP, CNRS, Institut Pascal, Université Clermont Auvergne, F-63000 Clermont-Ferrand, France
*
Author to whom correspondence should be addressed.
Sensors 2024, 24(6), 1909; https://doi.org/10.3390/s24061909
Submission received: 6 February 2024 / Revised: 7 March 2024 / Accepted: 14 March 2024 / Published: 16 March 2024
(This article belongs to the Special Issue Intelligent Transportation Systems: Sensing, Automation and Control)

Abstract

:
Evaluating the risk associated with operations is an essential element of safe planning and an essential prerequisite in mobile robotics. This issue is very broad, with numerous definitions emerging in the recent literature adapting different application scenarios and leading to different algorithmic approaches. In this review, we will investigate how the state-of-the-art approaches define the traversability risk, particularly for mobile robots, whereby we classify existing risk-aware navigation algorithms according to their characterization of risk. Subsequently, we will overview the formulations of risk assessment along a path using traversability grid maps since it is essential for a mobile robot to evaluate its path to predict potential hazards. Finally, we will discuss the consistency of commonly used risk metrics in robotics. The aim of the review is to offer a comprehensive overview to newcomers in the field, to provide a structured reference for practitioners, and to also inspire future developments.

1. Introduction

Currently, mobile robots are deployed to accomplish different missions in unknown and partially known structured or unstructured environments (see Figure 1). These missions include search and rescue operations prompted by natural disasters [1], the inspection of planetary terrains [2], agricultural robotics [3], military surveillance missions in off-road environments [4], and autonomous driving in urban environments [5]. These different missions in such different and complex environments cannot be achieved unless a few critical issues are addressed, namely (i) perceiving the environment, (ii) characterizing and identifying potential risks and building an environment model, (iii) assessing these risks, and (iv) planning optimal safe paths while controlling the robot based on the assessed risks. Considering the complexity and diversity of the challenges associated with these sub-problems, significant research efforts have been devoted to addressing them. Focusing on the first three ones, the ability to recognize its environment and translate the data it receives from its sensors into a useful amount of knowledge is crucial for any autonomous mobile robot. This capability enables the robot to decide whether it can navigate in a safe and efficient manner or not. In reality, this problem may incorporate machine learning, feature extraction, image and signal processing, and three-dimensional (3D) geometry, thereby leading to a wide range of approaches. Given the multitude of techniques employed in terrain comprehension and the diversity of terrains in which robots operate, this review aims to summarize traversability analysis methods and their associated risk assessments.
Our paper will be organized as follows: We first set out the definitions and taxonomy of traversability analysis. Then, we provide an overview of the different approaches that roboticists use to characterize risk in their risk-aware algorithms. Subsequently, we delve into the assessment of this risk along a path in grid-based environment models (mainly occupancy grid maps). Moving forward, we discuss the various risk metrics encountered in the literature and consider that probabilistic occupancy grids treat risk as a stochastic variable. Finally, we close our study with a brief general conclusion.

2. Related Works and Survey Boundaries

Reviewing the field of terrain traversability analysis has been performed in numerous earlier works. In [6], the author reviewed the field of 3D terrain traversability analysis by categorizing methodologies into three main constituents, namely proprioceptive, appearance-based, and geometry-based approaches. Furthermore, ref. [7] provided a survey of the field from the perspective of planetary exploration, in which they combined pertinent applications, current methods, and underlying techniques within a unified framework. Additionally, an extensive survey of methods for planetary terrains was given in [8], where applications regarding the dry and rocky surfaces on which the planetary rovers operated were found. Advancements adopting learning-based methods to solve the problem of environment perception and interpretation with the final aim of the autonomous context-aware navigation of ground vehicles in unstructured environments were also reviewed in [9]. Ref. [10] provided a survey on sensor data fusion techniques for obstacle detection, which are applicable in off-road navigation scenarios. A more recent survey that links many of the recent advancements in traversability analysis, particularly in machine learning and semantics with classical statistical methods, was also published [11]. An overview of the aforementioned surveys is provided in Table 1.
As a complement to the aforementioned studies, the main purpose of this article is to provide a comprehensive and general overview of the traversability risk characterizations and assessments that encompass the entire range of mobile robotic applications (urban, planetary, agricultural, etc.). Our focus is to link together both classical and learning-based methods, thereby emphasizing the risk perspective rather than the methodology itself. We have also included certain points that we deemed necessary for traversability risk analysis, such as assessing the risk along a path and examining existent risk metrics.

3. Taxonomy

Before we tackle the question of characterizing and quantifying risk, it is imperative to outline the broad notion of risk in mobile robotics. The wide range of applications for mobile robots leads to a large variety of risks and motivates the need for a field taxonomy.
Indeed, the risks differ from one application of a mobile robot to another. For instance, the risks encountered by a rover carrying out exploration missions on Mars are not the same as those encountered by an industrial mobile robot tasked with moving pallets in a factory shed. In the first case, the robot needs to keep an eye on its power consumption and also on massive impact craters, cliffs, cracks and jagged boulders. However, the risk for an industrial mobile robot is quite different. A simple classification of these risks can be achieved by categorizing according to their source. For unmanned ground vehicles (UGVs), we can distinguish two main classes: efficiency-based and traversability-based risks. The efficiency-based category includes such elements as battery consumption [12], loss of communication [13], etc. While the traversability-based category, which is the core of our study, encompasses all the risks associated with the nature of the ground (landform, speed bumps, pot holes, slopes, etc.) and the various static or dynamic obstacles encountered by the robot in its workspace, we specifically investigated traversability-based risk in this study (Figure 2).
Up to now, traversability analysis has been widely used as a means for the optimal navigation of UGVs in environments of varying complexity to ensure safety in terms of collisions or reaching unrecoverable states. Interestingly, this generic notion of traversability has been referred to using various terms such as drivability [14], navigability [15], trafficability [16], and maneuverability [17], thereby adding complexity to its formal definition within the robotics community. For instance, in [18], robotic traversability was formalized using the psychological concept of affordances that was introduced by [19]. The authors also provided the implementation results of one part of the affordance formalism for the learning and perception of traversability affordances on a mobile robot equipped with range sensing ability, and they showed that the robot, by interacting with its environment, can learn to perceive the traversability affordances. Although this formalization seems adequate, the authors in [6] argued that it was not formalized enough to quantify traversability and to derive a continuous measure instead of a binary assessment (either traversable or non-traversable), which made it overly generic and thus incomplete. And, in turn, they defined the traversability as “the capability of a ground vehicle to reside over a terrain region under an admissible state wherein it is capable of entering given its current state, this capability being quantified by taking into account a terrain model, the robotic vehicle model, the kinematic constraints of the vehicle and a set of criteria based on which the optimality of an admissible state can be assessed” [6] (p. 2). Furthermore, the authors of [8] defined the trafficability from the terrain perspective as the terrain’s aptitude to support and provide useful traction for robot navigation. A more recent definition was proposed in [11]. In their view, by contrasting the features of the terrain to the robot’s dynamics and kinematics capabilities, traversability analyzes the terrain at a more sophisticated level than obstacle detection and this leads to the creation of an environment cost map. Many factors, including the shape of the terrain, roughness, expected friction/traction, and the vehicle’s kinematics, might be included in the study. The authors of [20] proposed an approach whereby they explicitly measured the traversal cost, as well as the associated uncertainties. They called this cost ’traversability’ (i.e., a high traversability cost corresponds to an area of the environment where the robot may suffer damage or impediments).
For us, traversability in mobile robotics refers to the ability of a robot or autonomous vehicle to navigate through a given environment effectively and safely. This notion must be understood from both perspectives: the terrain and the robot. From a terrain perspective, traversability encompasses various factors such as terrain ruggedness, obstacles, slopes, stairs, and other environmental features that may hinder or facilitate the robot’s movement. On the other hand, traversability is also dependent on the robot’s kinematics and mechanical properties, such as speed, wheel size and type, chassis height, actuators, etc.
In this paper, for simplicity, the term ’risk’ refers to traversability-based risk (mainly with respect to collision).

4. Traversability Risk Characterization

It is becoming increasingly crucial to assess the risk involved in a robot’s course of action as an increasing number of autonomous systems are required to carry out safety-critical missions. So, the literature includes multiple methods that are used to characterize traversability risk, and these methods have been classified in different ways in previous reviews [6,8,21]. In our case, we opted to classify them into two main categories: sensor-based and map-based. Quite simply, the difference between the two is that the first family considers risk as a constraint in a global optimization problem (typically in path planning); therefore, it exploits perceptual information (i.e., sensor data) directly without converting it into a map. Whereas, for the second category, and as its name already indicates, a traversability map of the environment (which is commonly tessellated) is created to store an estimated traversability risk that is derived from the robot’s knowledge.

4.1. Sensor-Based Characterization

Following the boundary of an obstacle is a standard approach used by many earlier risk-averse navigation algorithms. In most cases, the risk is simply characterized by the minimum distance to the obstacle. In [22], for example, an approach for a collision-free boundary following obstacles of arbitrary shape and globally convergent path planning was proposed using the concept of instant goals. The risk analysis was performed simultaneously and, when needed, using a vector of the measured distance of each beam of the range finder sensor. Similarly, many path planning and model predictive control algorithms generate a probational path from the obstacle representation based on the sensor data at each time step, thereby ensuring a boundary following, such as the in the Bug family algorithms [23].
In [24], a sliding mode control law was proposed that leads the robot at a pre-specified distance from the obstacle’s boundary and maintains this distance afterward. In this approach, the risk is characterized by the sliding surface, which is a function of the length of the detection ray and the tangential angle of the obstacle at the intersection point.
In another fashion, ref. [25] defined risk in a way that accounts for the size of the obstacle (agent) and the vehicle. The authors fit circles of radius r to an agent and limited the likelihood that their centers are inside a suitably sized “collision ellipsoid” surrounding the vehicle, which formed the basis of their risk definition. The main distinction between their approach and standard deterministic path planning formulations lies in the chance constraint. This constraint ensures that the probability of the vehicle colliding with an agent does not exceed an upper bound at each time step. The authors in [26] approximated the chance-constrained problem as a disjunctive convex program that considers polyhedral stay-in regions and polyhedral obstacles instead of circles. Furthermore, an incremental sampling-based motion planning framework was proposed in [27] through distributionally robust chance constraints, wherein they considered both sensing and localization errors, stochastic process disruptions, erratic obstacle motion, and ambiguous obstacle positions.
Since wheel–terrain interactions play a critical role in rough terrain mobility, the authors of [28] proposed a technique for accurate traversability prediction based on an online estimation of key terrain parameters using on-board sensors. In their work, the estimated terrain parameters are the cohesion and internal friction angle, which can be used to compute the terrain shear strength and thus give an estimate of robot traversability. Similarly, the authors in [29] presented a learning-based method for terrain classification into a few predefined, commonly known categories such as gravel, sand, or asphalt. Then, the traversability is measured by determining a number of parameters such as the cohesion of the soil, the internal friction angle, the radial stress, the shear displacement, etc., which is achieved using multiple sensor modalities including inertial sensors, motor sensors, range sensors, and encoders.
Exponential utility functions are also a solution to represent risk [30]. The main finding of utility theory is that there exists a utility function that converts costs into real values, or “utilities”, such that maximizing expected utility is meaningful for any attitude toward risk. In the aforementioned work, the authors chose to use the exponential utility function u ( c ) = γ c , which was used to verify the property of “constant local risk aversion” and permitted them to express a whole spectrum of risk sensitivity. This spectrum ranges from being strongly risk-averse to being strongly risk-seeking in the function of the parameter γ . It is important to note here that c denotes the generalizable action cost (such as collision, resources consumption, etc.), which can be referred as the risk function for the Markov decision problem.
Since fuzzy logic has been widely applied in many fields, from control theory to artificial intelligence, it has also found its place among traversability risk analysis frameworks. In [31], the traversability risk is characterized by fuzzy rules. The authors proposed a rule-based Fuzzy Traversability Index that uses real-time measurements of the terrain attributes collected from imagery data to quantify how easy a terrain is for a mobile robot to traverse. These features include, but are not restricted to, discontinuity, slope, hardness, and roughness.
In [32], the authors represented the vehicles as particles, propagated the particles through their kinematics, and employed the resulting distribution as the risk distribution under the assumption that the geometry of the road layout is known from a high-definition map.
Quantile regression [33] is another prevalent choice to characterize risk in reinforcement learning-based frameworks. The authors in [34] introduced the Ensemble Quantile Networks (EQN) method, which combines distributional reinforcement learning with an ensemble approach to obtain a risk estimate. The distribution of risk is estimated by learning its quantile function implicitly. They demonstrated that their method can balance risk and time efficiency in different occluded intersection scenarios by considering the estimated risk. They estimated both the aleatoric uncertainty, which characterizes risk distribution (e.g., collision), and epistemic uncertainty, which arises due to the lack of knowledge and can be reduced by observing more data. In Table 2, an overview of the presented sensor-based approaches is provided, where they are further regrouped according to the targeted application and the features (criteria) used to define the traversability (Table 2).

4.2. Map-Based Characterization

Map-based approaches constitute another category of risk-aware navigation frameworks. As the name suggests, these techniques use an environment map as their input, which can be created from vehicle and terrain data using a variety of sensors including LiDAR, camera, IMU, GPS, and wheel odometry. Generally, the map depicts features related to terrain traversability in a tessellated fashion.
Let us start with the well-known standard of Bayesian occupancy grids [35], which model the environment by employing a probabilistic, tessellated representation of multi-source spatial data. In this framework, the map is kept as a grid of cells, each representing a small portion of the environment and possessing a value that indicates the occupancy probability of the specific element. These occupancy probabilities are updated using a Bayesian filter that treats each grid cell as an independent entity. Risk is therefore associated with the probability of occupancy. Initially developed as a 2D modeling tool, occupancy grids can be readily extended to 3D. However, 3D occupancy grids are memory-intensive, thus making them impractical for large-scale mapping applications.
In the same fashion (i.e., using the regular grid representation), many traversability maps have appeared in the literature. For instance, a traversability map was proposed by [36]. They projected the detection results of multiple sensors on a 2D probabilistic grid format, where each cell value can be understood as a probability that the vehicle can successfully drive over rather than probability occupancy (i.e., more traversability factors are taken into account such as the terrain slope). The derivation of probabilities varies depending on the sensor, with detailed steps provided for 3D LiDAR and RGB camera sensors. In [37], the authors constructed their traversability map by incorporating three fundamental terrain characteristics for each cell: the slope value, the curvature value, and the roughness. Meanwhile, in [38], the authors developed a simple traversability map where each cell of the grid contains the list of coordinates of the points falling within its bounds. Terrain classification is then performed for every cell individually using some criteria such as height variation, orientation of the vector normal to the path of terrain, and the presence of discontinuity of elevation in the cell.
In [39], the authors proposed a technique to compute a vector measure of the physical density of a given environment as perceived by each sensor modality using data from multiple sensors. Each cell of their ’density map’ consists of a feature set composed of two parts: a vector of floating point ’density’ measurements and a few auxiliary parameters. The floating point values represent the strength of the signal return from a single sensor in a single patch of the terrain. Measurements of the lowest and maximum height readings from the terrain, along with color information, are examples of auxiliary parameters.
The traversability index, firstly proposed by [40], serves to efficiently address a terrain’s ease of traversal for planetary rovers. This index represents the degree of ease with which the regional terrain could be navigated, and it is characterized by a number of fuzzy sets. In [41], the risk within each cell is expressed through its grade of membership to predefined fuzzy sets that are based on major surface features such as hills and lakes within a long range of the robot. The two main distinctions between their traversability grid and the Bayesian occupancy grid are as follows: (1) the probability of obstacle presence versus a more general concept of graded terrain quality, and (2) probability theory versus possibility theory using fuzzy sets. The authors of [42] created traversability indexes using fuzzy logic that depend on the terrain’s slope, roll variance, and roughness. They integrated fuzzy inference to combine these terrain features in order to obtain a traversability assessment and local quantitative evaluation. In [43], a method was suggested that transforms a local terrain map around the robot’s current position into a grid-type traversability map. This transformation involves extracting slope and roughness information from terrain patches using least-squares plane fitting. Subsequently, the method calculates ’polar obstacle densities’ for each cell in the traversability map and converts them into a traversability field histogram.
The 2.5D Digital Elevation Map (DEM), alternatively known as Cartesian elevation maps [44,45], is another option for traversability risk characterization as it extends the concept of 2D occupancy grids. This mapping technique stores the cell’s elevation instead of its occupancy probability. The DEM is the most widely used technique for environment modeling and traversability analysis. Therefore, several modifications have been proposed to improve its efficiency such as in [46], who considered the elevation to follow a Gaussian distribution, and the stores for each cell are not only the mean elevation, but also the variance. Although elevation maps offer compact representation, they may not adequately depict multi-level structures or even vertical structures (bridges, for instance). Therefore, the authors of [47] proposed a new representation denoted as multi-level surface maps (MLS maps), which allows one to store the elevation of multiple surfaces in each cell of the grid. However, surface representations are frequently based on significant assumptions about the corresponding environment, and they may demand a large amount of memory, especially outdoors. Additionally, they may not effectively differentiate between free and unknown space, which is crucial for safe navigation. Addressing this limitation, the authors of [48] proposed a three-dimensional model using octrees [49], thereby providing a volumetric representation of space and employing probabilistic occupancy estimation. In this model, each voxel stores a probability of occupancy that is similar to the standard Bayesian occupancy 2D grid. A visualization of the mapping results for the same environment (a tree) using some of the 3D mapping approaches mentioned in this paragraph is shown in Figure 3.
Moreover, the authors in [50] asserted that all the previously mentioned frameworks were not suitable for assessing meaningful risks, i.e., risks that keep their physical unit. Thus, they proposed a novel framework called Lambda-field, which is based on the Poisson Point Process theory. Their map stores for each cell the ‘rate’ λ of a harmful event (i.e., collision) instead of the probability of occupancy. A higher intensity λ indicates a greater likelihood of collision at a given position (see Figure 4). The Lambda-field framework permits the computation of risk along a given path while retaining its physical sense, without resorting to probabilistic forms, by simply integrating the intensity of ‘ λ ’. In addition, using their framework, one can choose any risk function, whether associated with the nature of the robot or that of the terrain, without any change in the theory. In their case, for instance, they take the maximum gain in kinetic energy that results from a collision as the risk function.
Furthermore, a 3D extension of the Lambda-field framework is proposed in [52], wherein they consider the time of a harmful event to be the deformation of the wheel due to a collision, and they consider the risk function as being the maximum potential energy that is absorbed by the wheels. So, they store, for each cell, the intensity of being non-crossable by the robot. In [53], we assumed that the traversability risk stems not only from collision, but also from the lack of knowledge at each position. To address this, a new map called the ’knowledge map’ was introduced, where a probability of knowledge for each cell is stored. This map was then combined with a Bayesian occupancy grid to assess the traversability risk along a path.
Learning-based cost maps have seen more recent developments for robotics and autonomous driving. In [54], an architecture was proposed wherein raw or minimally processed point cloud data are transformed and introduced into a convolutional neural network (CNN), which then generate a CVaR (Conditional Value at Risk) cost map directly. The obtained traversability cost map was more robust to outliers because of the use of CVaR, and it was more computationally efficient. In [55], the authors argued that a neural network may be trained in a self-supervised manner to examine the traversability of terrain using the empirical distribution of traction parameters in unicycle dynamics. The proposed approach takes, as the input, local semantic and elevation features to predict linear and angular traction distributions in order to generate a traction distribution map. The map indicates the reliability of the prediction, such that if the likelihood of input terrain features is below a threshold, the terrain is deemed out-of-distribution (OOD) and later avoided during planning via auxiliary penalties. In [56], the authors proposed a novel interpretation of a terrain’s traversability by learning speed and gait policies based on terrain semantics and human demonstrations. The resulting ’speed map’ provided a straightforward and intuitive understanding of the model’s predictions, and it can be used in navigational tasks such as path planning. Ref. [57] uses privileged information during training to learn navigational affordances in a modular manner, where perfect odometry availability is assumed. The authors proposed to construct a top-down belief map of the world (i.e., the mapping is driven by the needs of the planner), and they applied a differentiable neural net planner to produce the next action at each time step. In [58], the authors provided an MMP-based approach with non-linear cost functions [59], in which they integrated multiple on-board sensor features such as obstacle heights and LiDAR point densities. The learned cost map, derived from an expert’s demonstration and based on detected perceptual features, is used by the two-level planner of a six-wheeled skid steer vehicle. Table 3 summarizes the map-based traversability analysis methods discussed so far.
Despite the fact that, up to now, we have only been talking about methods that discretize the environments into cells, since this is the subject of the rest of this study, it is not the only solution available. Another solution was provided in [60], in which the environment was represented as a Gaussian process (GP). The main idea is that, for each position, the GP defines the occupancy as a Gaussian distribution, one that is characterized by a mean μ and an associated predictive variance σ . This utilization of a Gaussian process entails a non-parametric Bayesian learning technique, thereby enabling the exploitation of correlations between points on the map. This aspect is not addressed by mapping techniques like the occupancy grids mentioned earlier. To answer the drawbacks of the GP approach, the authors of [61] proposed a simpler and faster approach for environment representation through continuous occupancy mapping. The technique, named Hilbert maps, represent the occupancy property of the world with a linear discriminative model operating on a high-dimensional feature vector that projects observations into a reproducing kernel Hilbert space. Just like the GP, this approach provides maps at any resolution since it does not presuppose that the world is divided into grid cells and naturally captures the spatial correlations between measurements.
Until now, our discussion has revolved around risk mapping methods tailored for static environments. However, traversability risk may also arise from dynamic obstacles, as previously mentioned. In this context, the issue of creating continuous occupancy maps of dynamic environments for robotics applications is addressed in [62] by learning a kernel classifier on an efficient feature space. They incorporated the temporal variations into the spatial domain by propagating motion uncertainty into the kernel using a hierarchical model that enables a direct prediction of future occupancy maps from past observations. Although fast optimization methods and heuristic tuning were required, ref. [63] proposed a Bayesian approach to address this issue, thus eliminating the regularization term of Hilbert maps. They extended this approach to deal with dynamic environments by leveraging neighborhood information to reduce susceptibility to occlusions. While the initial formalization of Hilbert maps may not fully support their methods, their implementation underscores the utility of Bayesian methods for dynamic environments. In a more recent work [64], the authors proposed a framework that allows for a real-time computation of the previous approach. It aims to capture the uncertainty of moving objects, and this uncertainty information is then incorporated into the Hilbert maps. Nevertheless, their models currently struggle to track complex patterns and only deal with simple motion models. Additionally, ref. [65] addressed the dynamic occupancy grid issues by presenting a stereo-vision-based framework. It consists of two components: a motion estimation for both the moving ego-vehicle and the independent moving objects; and dynamic occupancy grid mapping, which relies on the estimated motion information and dense disparity maps. Despite its ability to map occupied areas and moving objects concurrently, further optimization is needed, especially when multiple objects are present, to meet real-time constraints.
Another group of frameworks [66,67,68] offered an alternative approach for dealing with dynamic and occluded objects. In [66], Markov chains were used to model the dynamics of moving pedestrians and to predict their potential future locations. These occlusion estimations are mapped into risk regions and then employed to plan a path through a potentially obstructed area. Similarly, ref. [68] introduced the same idea. By analyzing the scene and evaluating the best possible future behavior, the authors proposed to map the expected risk according to the dynamic variations of the acting ’entities’. Their predictive risk map indicates how risky a certain behavior will be in the future and enables the evaluation of risk-minimizing behavior on path planning.
With the rise of neural networks, some of the literature [69,70] advocates for machine learning approaches in dynamic traversability mapping. The authors of [69] tackled the velocity estimation errors highlighted in [71] using a recurrent neural network architecture. Meanwhile, ref. [70] tackled the issues related to dynamic occupancy grid maps by combining a Bayesian filtering technique and a deep convolutional neural network. These works provided efficient segmentation of the static and dynamic zones. However, the performance of such methods sorely depend on the dataset used for training. More generally, the big drawback of learning methods is the training step.

5. Risk Assessments along a Path in Traversability Grid Maps

In the preceding section, we provide a comprehensive overview of traversability risk characterizations in terrestrial mobile robot navigation frameworks. These are classified into two main categories: sensor-based and map-based. In this section, our focus shifts to the second category, which more specifically assesses the risk along a path using traversability grids. These metric maps are particularly well suited for risk assessment since they tessellate the environment into cells where each one stores the information about potential risky event (such as collision, elevation, roughness, lack of knowledge, etc.). Given that the environment, represented as a field e : R n R , possesses an infinite number of degrees of freedom, which makes it non-storable on a machine, tessellating the environment into cells of fixed size and assuming that the field is constant inside the cells is the most appropriate solution for assigning an occupation to each position in the environment.
In [72], the authors used the occupancy grid to simply make a binary classification of the cells (either occupied or free according to a predefined threshold). Subsequently, each cell was assigned a reward according to its occupancy status, with positive values denoting occupied cells and negative values indicating free cells. By summing up the rewards of all the cells along a given path, they could obtain an occupancy cost for the path. This allows for a comparison of the various trajectories from a list of tentacles, where the safest trajectory is selected as the one yielding the highest reward.
If we continue to utilize the standard Bayesian occupancy grids, and if we reduce for now the risk to the probability of collision, the risk of crossing a path P [ 0 , i ] given by a set of i cells is as follows:
R ( P [ 0 , i ] ) = 1 j = 0 i ( 1 P j ) ,
where P j is the probability of occupation of the j t h cell.
Another probabilistic definition of risk is ’the probability of the robot not being able to finish the path’, which was proposed in [73]. Its expression is given by the following:
R ( P [ 0 , i ] ) = 1 j = 0 i k = 0 r ( 1 r k ) ,
where r k is the probability of occupied cell k causing failures at state j given the history of finishing the cells with indexes from 0 to j.
In [74], the authors assumed that Equation (1) is valid only if P j is defined as the probability of a collision to occur within the corresponding time interval and that it can possibly normalized as such; otherwise, the definition of R ( P [ 0 , i ] ) would depend on the time step. Thus, they defined a temporal risk function called TTC (Time To Collision) τ ( P [ 0 , n ] ) as the expectancy of the time of the first collision. Its expression is given by Equation (3).
τ ( P [ 0 , n ] ) = t 0 R ( P 0 ) + i = 1 n t i R ( P [ 0 , i ] ) ( 1 R ( P [ 0 , i 1 ] ) )
Although Equation (1) seems very reasonable, because the risk here is none other than the probability of colliding at least one cell in the path (which is the complement of the joint probability that all cells are free), the authors in [50] were able to show that the above calculation is ill-formed. This was illustrated using the example depicted in Figure 5.
In this case, if we simply apply the above equation to evaluate the risk over the two (orange and blue) paths leading to the objective, we will find that the probability of collision of the orange one has a value of 0.97 , while that of the blue is 0.99 . As such, instead of choosing the blue path, which seems intuitively more safe, the robot would take the orange one, which passes through a large number of highly occupied cells. Additionally, they highlighted that the probability of collision was significantly influenced by the discretization. An illustrative example is shown in Figure 6.
Through this example, we can see that the two scenarios produced different collision probabilities, whereas the robots crossed the same uniform probability field.
These limitations prompted the authors to find more appropriate solutions. For example, the authors in [75] considered the risk over a path to be a measure of the expected loss. The expectation, in this case, was taken over the probability that the vehicle will collide with an obstacle at cell c. Hence, the risk is expressed by the following:
R ( P ) = i = 0 N 1 P i · L ( x v , x c ) ,
where L ( x v , x c ) is the loss as a function of the vehicle state x v and the cell state x c . In their work, they defined risk as the total loss of kinetic energy of the system. This was also the same for [53], wherein they defined risk as the integral over the trajectory (expected value) of the kinetic energy of contact, which is weighted by a probability of risk.
Indeed, in this case, risk R is not a probability of collision as it lies in [ 0 , ) , but rather it represents a kinetic energy expressed in (Joule), i.e., this time it has a physical meaning but is still dependent on the tessellation size—the smaller the size of the cells, the more cells the robot lies on and therefore the larger R is.
Furthermore, we can consider the case represented by Figure 7, where the robot needs to choose between the two paths (top and bottom) by assessing the risk using Equation (4).
If we consider that the robot has a mass m and runs at constant speed v, it becomes evident that both trajectories would have the same risk value. However, it is apparent that the second trajectory was more risky due to an 80% occupied cell.
The risk was therefore multiplied by the cell area Δ a , as one suggested a solution to the cell size dependency issue.
R ( P ) = Δ a i = 0 N 1 P i · L ( x v , x c )
But, by multiplying by the area, we lose the physical meaning of R ( P ) (i.e., this is leading to the risk being expressed in J · m 2 ).
Another solution to infer the probability of collision in occupancy grids was proposed in [76]. They proposed a new interpretation of risk that accounts for the fraction of time that a robot has stayed in a cell while following a trajectory using the theory of product integrals [77]. The probability of collision based on this theory is then given by the following:
R ( P ) = 0 L [ 1 p 0 ( P ) ) ] d s ,
where p 0 denotes the probability of collision over P . We should note here that one of the drawbacks of their approach is that the robot is reduced to a point (i.e., the robot’s wheelbase is zero).
Therefore, the probability of collision does not rely on the size of the tessellation when we integrate over the tessellated field.
In addition, the authors in the already-cited paper [20] used the time consistency dynamic risk measure [78], which is defined for a set of states x 0 : N and a policy π , as per the following:
J ( x 0 , π ; m ) = R 0 + ρ 0 ( R 1 + ρ 1 ( R 2 + . . . + ρ N 1 ( R N ) ) ) ,
where ρ denotes the conditional value at risk ( C V a R α ) , which was discussed in the following section; and R i , which depicts the risk for time i. Moreover, for α 0 , the risk function J simplifies to
lim α 0 J ( x 0 , π ; m ) = R 0 + E [ R 1 + E [ R 2 + + E [ R N ] ] ] , = R 0 + i = 1 N E [ R i ] .
One can easily notice that the smaller the discretization, the higher the risk (i.e., when the number of sample times increases to infinity, the risk tends to infinity).
When discussing the dependence on cell size and the physical sense of risk, we cannot avoid citing [50]. In that study, the authors proposed a new framework for not only representing cell occupancy differently (as mentioned in the previous paragraph), but also for assessing physical risk over a path. They defined the probability of encountering at least one collision on the path as follows:
R ( P ) = P f ( a ) d a 1 exp ( A c i λ i ) ,
where f ( a ) is the probability distribution associated to the Lambda-field framework as a function of the traveled area a. Each cell c i has an area A and an associated lambda λ i .
In addition, by choosing a physical risk function (force of collision, energy, etc.) r ( · ) , they defined its expectation over the path P going through the cells { c i } 0 : N by the following:
E [ r ( X ) ] = i = 0 N r ( A i ) exp ( A j = 0 i 1 λ j ) ( 1 exp ( A λ i ) ,
where X is the position (i.e., area) at which the first event ‘collision’ occurs. Although the Lambda-field framework is not yet popular among the robotics community, it remains a very suitable choice for assessing the physical risk along a path.

6. Quantification Metrics for Stochastic Risk

In most cases, and especially in grid-based maps, the risk is a stochastic variable. A map is fundamentally, most of the time, a field of binary random variables. A sensor is a probabilistic channel that links robot motion in the physical world to information gain. Quantifying risk, then, corresponds to evaluating a risk metric, i.e., a mapping from the cost random variable to a real number.
As such, ref. [79] provided an exhaustive study of what constitutes a ’good’ risk metric by advocating axioms that must be fulfilled by the latter:
  • A1. Monotonicity;
  • A2. Translation invariance;
  • A3. Positive homogenity;
  • A4. Subadditivity;
  • A5. Comonotonic additivity;
  • A6. Law invariance.
The expected value used, for instance, in [50] describes the long-term average level of risk based on its probability distribution. It constitutes a simple and coherent metric in the sense that it satisfies all of the axioms of [79], as well as the worst case metric [80], which refers simply to the largest value of risk. Another popular metric to quantify risk in robotics applications is the mean variance E [ X ] + β V a r [ X ] , which is used—for instance—in [81]. The mean variance satisfies only the axiom ’A6’, thereby rendering it a non-coherent metric.
In addition to statistics, finance specialists also have their own risk metrics, which are increasingly used in robotics. One should start with the most popular Value at Risk (VaR), which is defined as the ( 1 α ) -quantile of the cost distribution. Its expression is given in Equation (11).
VaR α ( X ) = m i n { x | P ( X > x ) α } .
In actuality, VaR is a non-coherent risk metric since it satisfy only five axioms. In line with the aforementioned chance constraints [25,26,27], the VaR was found to be closely related since the constraint V a r α ( Z ) 0 corresponded to the chance constraint P ( X > 0 ) α .
The expected shortfall, or the Conditional Value at Risk (CVaR) metric [82], was introduced in several risk-aware path planning applications [20,83] as an alternative to VaR. Intuitively, CVaR is the expected value of costs in the conditional distribution of the cost distribution’s upper ( 1 α ) -tail; thus, it is a metric of ’how bad is bad’. Moreover, the CVaR can be expressed as a function of VaR as follows:
CVaR α ( Z ) : = 1 α ( 1 α ) 1 V a R 1 τ ( Z ) d τ .
As we said before, VaR has some shortcomings and that is why CVaR, which is a coherent risk metric, comes in handy.
Entropic Value at Risk (EVaR) [84] is another financial risk metric that has been adopted for mobile robot risk assessment applications [85]. EVaR is an upper bound for both the value at risk (VaR) and the conditional value at risk (CVaR), which is obtained from the Chernoff inequality.
E V a R 1 α ( X ) = inf z > 0 z 1 ln E [ e X z ] 1 α .
Even though both the EVaR and the CVaR are coherent metrics, EVaR is a more risk-sensitive measure.
A comparison of the most used risk metrics is illustrated in Figure 8.
In [87], the authors presented a new risk measure that is a generalization of EVaR called Relativistic Value at Risk (RLVaR). It is a special case of ϕ divergence risk measures based on Kaniadakis entropy. The RLVaR is a coherent risk metric that has not yet been adopted in robotics.
An overview of the discussed risk metrics is provided in Table 4, which was achieved by determining their coherence according to [79].

7. Conclusions and Future Works

In this review, we provided a glance at the main methods that are to define and assess risk in mobile robotics applications. The risk characterization approaches have been divided into two main categories: sensor-based and map-based methods. In contrast to the second category, which does require transforming sensor data into an environment map (mainly in grid format), the first family includes all of the methods that utilize sensor data without such transformations. Map-based methods produce accurate metric maps that encode the traversability information and allow for efficient risk-aware planning. However, this efficiency decreases in large-scale indoor environments. Sensor-based methods also enable efficient reactive navigation but lack a suitable model of the environment. We then focused our study on the second category by dealing with the assessment of traversability risk along a path in such traversability grids. Several formulations were discussed, wherein we highlighted their drawbacks and used some examples. We opted to end this mini-review by discussing the various existing risk metrics, which represent an important field in robotic risk assessment applications. Thus, investigating these risk metrics led to the conclusion that not all of them exhibit coherence, and certain metrics stand out as objectively superior to others.
The present paper has outlined several major advances and breakthroughs in the field of traversability analysis. This represents a solid foundation for our future work, where the aim is to develop a risk-aware navigation framework that enables an autonomous vehicle to operate efficiently in urban environments with numerous sources of information available, as well as in off-road or rural zones. To achieve this objective, a traversability analysis must be carried out that takes into account all of the aspects ranging from the nature of the terrain, through the robot’s mechanical limitations, to an analysis of the robot’s knowledge (i.e., perception capabilities and information availability), as initiated in our earlier work [53].

Author Contributions

Conceptualization, M.B., C.O.M., R.C. and R.A.; methodology, M.B., R.C. and R.A.; validation, M.B., C.O.M., E.R., R.C. and R.A.; formal analysis, M.B., C.O.M. and E.R.; investigation, M.B.; resources, M.B., C.O.M., R.C. and R.A.; data curation, M.B.; writing—original draft preparation, M.B.; writing—review and editing, M.B., C.O.M., E.R., R.C. and R.A.; visualization, M.B.; supervision, R.C. and R.A.; project administration, R.C. and R.A. 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

The data are contained within the article.

Acknowledgments

This work was supported by the International Research Center ”Innovation Transportation and Production Systems” of I-SITE CAP 20-25.

Conflicts of Interest

The authors declare no conflicts of interest.

Abbreviations

The following abbreviations are used in this manuscript:
UGVUnmanned Ground Vehicles
EQNEnsemble Quantile Networks
IMUInertial Measurement Unit
GPSGlobal Positioning System
DEMDigital Elevation Map
MLSMulti-Level Surface
CNNConvolutional Neural Network
CVaRConditional Value at Risk
OODOut Of Distribution
MMPMaximum Margin Planning
GPGaussian Process
TTCTime To Collision
VaRValue at Risk
EVaREntropic Value at Risk
RLVaRRelativistic Value at Risk

References

  1. Nagatani, K.; Kiribayashi, S.; Okada, Y.; Otake, K.; Yoshida, K.; Tadokoro, S.; Nishimura, T.; Yoshida, T.; Koyanagi, E.; Fukushima, M.; et al. Emergency response to the nuclear accident at the Fukushima Daiichi Nuclear Power Plants using mobile rescue robots. J. Field Robot. 2013, 30, 44–63. [Google Scholar] [CrossRef]
  2. Husain, A.; Jones, H.; Kannan, B.; Wong, U.; Pimentel, T.; Tang, S.; Daftry, S.; Huber, S.; Whittaker, W.L. Mapping planetary caves with an autonomous, heterogeneous robot team. In Proceedings of the 2013 IEEE Aerospace Conference, Big Sky, MT, USA, 2–9 March 2013; pp. 1–13. [Google Scholar]
  3. Åstrand, B.; Baerveldt, A.J. An agricultural mobile robot with vision-based perception for mechanical weed control. Auton. Robot. 2002, 13, 21–35. [Google Scholar] [CrossRef]
  4. Naranjo, J.E.; Clavijo, M.; Jiménez, F.; Gomez, O.; Rivera, J.L.; Anguita, M. Autonomous vehicle for surveillance missions in off-road environment. In Proceedings of the 2016 IEEE Intelligent Vehicles Symposium (IV), Gothenburg, Sweden, 19–22 June 2016; pp. 98–103. [Google Scholar]
  5. Dikmen, M.; Burns, C.M. Autonomous driving in the real world: Experiences with tesla autopilot and summon. In Proceedings of the 8th International Conference on Automotive User Interfaces and Interactive Vehicular Applications, Ann Arbor, MI, USA, 24–26 October 2016; pp. 225–228. [Google Scholar]
  6. Papadakis, P. Terrain traversability analysis methods for unmanned ground vehicles: A survey. Eng. Appl. Artif. Intell. 2013, 26, 1373–1385. [Google Scholar] [CrossRef]
  7. Sancho-Pradel, D.L.; Gao, Y. A survey on terrain assessment techniques for autonomous operation of planetary robots. JBIS-J. Br. Interplanet. Soc. 2010, 63, 206–217. [Google Scholar]
  8. Chhaniyara, S.; Brunskill, C.; Yeomans, B.; Matthews, M.; Saaj, C.; Ransom, S.; Richter, L. Terrain trafficability analysis and soil mechanical property identification for planetary rovers: A survey. J. Terramechanics 2012, 49, 115–128. [Google Scholar] [CrossRef]
  9. Guastella, D.C.; Muscato, G. Learning-based methods of perception and navigation for ground vehicles in unstructured environments: A review. Sensors 2020, 21, 73. [Google Scholar] [CrossRef]
  10. Hu, J.w.; Zheng, B.y.; Wang, C.; Zhao, C.h.; Hou, X.l.; Pan, Q.; Xu, Z. A survey on multi-sensor fusion based obstacle detection for intelligent ground vehicles in off-road environments. Front. Inf. Technol. Electron. Eng. 2020, 21, 675–692. [Google Scholar]
  11. Borges, P.; Peynot, T.; Liang, S.; Arain, B.; Wildie, M.; Minareci, M.; Lichman, S.; Samvedi, G.; Sa, I.; Hudson, N.; et al. A survey on terrain traversability analysis for autonomous ground vehicles: Methods, sensors, and challenges. Field Robot 2022, 2, 1567–1627. [Google Scholar] [CrossRef]
  12. Berenz, V.; Tanaka, F.; Suzuki, K. Autonomous battery management for mobile robots based on risk and gain assessment. Artif. Intell. Rev. 2012, 37, 217–237. [Google Scholar] [CrossRef]
  13. Ghabcheloo, R.; Aguiar, A.P.; Pascoal, A.; Silvestre, C.; Kaminer, I.; Hespanha, J. Coordinated path-following control of multiple underactuated autonomous vehicles in the presence of communication failures. In Proceedings of the 45th IEEE Conference on Decision and Control, San Diego, CA, USA, 13–15 December 2006; pp. 4345–4350. [Google Scholar]
  14. Neuhaus, F.; Dillenberger, D.; Pellenz, J.; Paulus, D. Terrain drivability analysis in 3D laser range data for autonomous robot navigation in unstructured environments. In Proceedings of the 2009 IEEE Conference on Emerging Technologies & Factory Automation, Palma de Mallorca, Spain, 22–25 September 2009; pp. 1–4. [Google Scholar]
  15. Yun, J.; Miura, J. A quantitative measure for the navigability of a mobile robot using rough maps. In Proceedings of the 2008 IEEE/RSJ International Conference on Intelligent Robots and Systems, Nice, France, 22–26 September 2008; pp. 3458–3464. [Google Scholar]
  16. Ojeda, L.; Borenstein, J.; Witus, G. Terrain trafficability characterization with a mobile robot. In Proceedings of the Unmanned Ground Vehicle Technology VII, Orlando, FL, USA, 28 March–1 April 2005; Volume 5804, pp. 235–243. [Google Scholar]
  17. Kim, J.; Lee, J. Predicting maximum traction to improve maneuverability for autonomous mobile robots on rough terrain. J. Autom. Control Eng. 2013, 1, 1–6. [Google Scholar] [CrossRef]
  18. Uğur, E.; Şahin, E. Traversability: A case study for learning and perceiving affordances in robots. Adapt. Behav. 2010, 18, 258–284. [Google Scholar] [CrossRef]
  19. Gibson, J.J. The ecological approach to the visual perception of pictures. Leonardo 1978, 11, 227–235. [Google Scholar] [CrossRef]
  20. Fan, D.D.; Otsu, K.; Kubo, Y.; Dixit, A.; Burdick, J.; Agha-Mohammadi, A.A. Step: Stochastic traversability evaluation and planning for risk-aware off-road navigation. arXiv 2021, arXiv:2103.02828. [Google Scholar]
  21. Sevastopoulos, C.; Konstantopoulos, S. A survey of traversability estimation for mobile robots. IEEE Access 2022, 10, 96331–96347. [Google Scholar] [CrossRef]
  22. Ge, S.S.; Lai, X.; Mamun, A.A. Boundary following and globally convergent path planning using instant goals. IEEE Trans. Syst. Man, Cybern. Part B (Cybern.) 2005, 35, 240–254. [Google Scholar] [CrossRef]
  23. Mastrogiovanni, F.; Sgorbissa, A.; Zaccaria, R. Robust navigation in an unknown environment with minimal sensing and representation. IEEE Trans. Syst. Man, Cybern. Part B (Cybern.) 2008, 39, 212–229. [Google Scholar] [CrossRef] [PubMed]
  24. Matveev, A.S.; Hoy, M.C.; Savkin, A.V. The problem of boundary following by a unicycle-like robot with rigidly mounted sensors. Robot. Auton. Syst. 2013, 61, 312–327. [Google Scholar] [CrossRef]
  25. Wang, A.; Jasour, A.; Williams, B.C. Non-gaussian chance-constrained trajectory planning for autonomous vehicles under agent uncertainty. IEEE Robot. Autom. Lett. 2020, 5, 6041–6048. [Google Scholar] [CrossRef]
  26. Blackmore, L.; Ono, M.; Williams, B.C. Chance-constrained optimal path planning with obstacles. IEEE Trans. Robot. 2011, 27, 1080–1094. [Google Scholar] [CrossRef]
  27. Renganathan, V.; Shames, I.; Summers, T.H. Towards integrated perception and motion planning with distributionally robust risk constraints. IFAC-PapersOnLine 2020, 53, 15530–15536. [Google Scholar] [CrossRef]
  28. Iagnemma, K.; Shibly, H.; Dubowsky, S. On-line terrain parameter estimation for planetary rovers. In Proceedings of the Proceedings 2002 IEEE International Conference on Robotics and Automation (Cat. No. 02CH37292), Washington, DC, USA, 11–15 May 2002; Volume 3, pp. 3142–3147. [Google Scholar]
  29. Ojeda, L.; Borenstein, J.; Witus, G.; Karlsen, R. Terrain characterization and classification with a mobile robot. J. Field Robot. 2006, 23, 103–122. [Google Scholar] [CrossRef]
  30. Koenig, S.; Simmons, R.G. Risk-sensitive planning with probabilistic decision graphs. In Principles of Knowledge Representation and Reasoning; Elsevier: Amsterdam, The Netherlands, 1994; pp. 363–373. [Google Scholar]
  31. Howard, A.; Seraji, H.; Tunstel, E. A rule-based fuzzy traversability index for mobile robot navigation. In Proceedings of the Proceedings 2001 ICRA. IEEE International Conference on Robotics and Automation (Cat. No.01CH37164), Seoul, Republic of Korea, 21–26 May 2001; Volume 3, pp. 3067–3071. [Google Scholar] [CrossRef]
  32. Yu, M.Y.; Vasudevan, R.; Johnson-Roberson, M. Occlusion-aware risk assessment for autonomous driving in urban environments. IEEE Robot. Autom. Lett. 2019, 4, 2235–2241. [Google Scholar] [CrossRef]
  33. Dabney, W.; Rowland, M.; Bellemare, M.; Munos, R. Distributional reinforcement learning with quantile regression. In Proceedings of the AAAI Conference on Artificial Intelligence, New Orleans, LA, USA, 2–7 February 2018; Volume 32. [Google Scholar]
  34. Hoel, C.J.; Wolff, K.; Laine, L. Ensemble quantile networks: Uncertainty-aware reinforcement learning with applications in autonomous driving. IEEE Trans. Intell. Transp. Syst. 2023, 24, 6030–6041. [Google Scholar] [CrossRef]
  35. Elfes, A. Using occupancy grids for mobile robot perception and navigation. Computer 1989, 22, 46–57. [Google Scholar] [CrossRef]
  36. Sock, J.; Kim, J.; Min, J.; Kwak, K. Probabilistic traversability map generation using 3D-LIDAR and camera. In Proceedings of the 2016 IEEE International Conference on Robotics and Automation (ICRA), Stockholm, Sweden, 16–21 May 2016; pp. 5631–5637. [Google Scholar]
  37. Li, S.; Song, R.; Zheng, Y.; Zhao, H.; Li, Y. Rugged-terrain traversability analyzing for quadruped robots. In Proceedings of the 2019 2nd International Conference of Intelligent Robotic and Control Engineering (IRCE), Singapore, 25–28 August 2019; pp. 1–6. [Google Scholar]
  38. Langer, D.; Rosenblatt, J.K.; Hebert, M. An integrated system for autonomous off-road navigation. In Intelligent Unmanned Ground Vehicles: Autonomous Navigation Research at Carnegie Mellon; Springer: Boston, MA, USA, 1997; pp. 259–275. [Google Scholar]
  39. Ollis, M.; Jochem, T.M. Structural method for obstacle detection and terrain classification. In Proceedings of the Unmanned Ground Vehicle Technology V, Orlando, FL, USA, 21–25 April 2003; Volume 5083, pp. 1–12. [Google Scholar]
  40. Seraji, H. Traversability index: A new concept for planetary rovers. In Proceedings of the Proceedings 1999 IEEE International Conference on Robotics and Automation (Cat. No. 99CH36288C), Detroit, MI, USA, 10–15 May 1999; Volume 3, pp. 2006–2013. [Google Scholar]
  41. Seraji, H. New traversability indices and traversability grid for integrated sensor/map-based navigation. J. Robot. Syst. 2003, 20, 121–134. [Google Scholar] [CrossRef]
  42. Huajun, L.; Jingyu, Y.; Chunxia, Z. A generic approach to rugged terrain analysis based on fuzzy inference. In Proceedings of the ICARCV 2004 8th Control, Automation, Robotics and Vision Conference, 2004, Kunming, China, 6–9 December 2004; Volume 2, pp. 1108–1113. [Google Scholar]
  43. Ye, C.; Borenstein, J. A method for mobile robot navigation on rough terrain. In Proceedings of the IEEE International Conference on Robotics and Automation, 2004. Proceedings. ICRA’04. 2004, New Orleans, LA, USA, 26 April–1 May 2004; Volume 4, pp. 3863–3869. [Google Scholar]
  44. Daily, M.J.; Harris, J.G.; Keirsey, D.M.; Olin, K.E.; Payton, D.W.; Reiser, K.; Rosenblatt, J.K.; Tseng, D.Y.; Wong, V. Autonomous cross-country navigation with the ALV. In Proceedings of the Proceedings. 1988 IEEE International Conference on Robotics and Automation, Philadelphia, PA, USA, 24–29 April 1988; Volume 2, pp. 718–726. [Google Scholar]
  45. Olin, K.E.; Tseng, D.Y. Autonomous cross-country navigation: An integrated perception and planning system. IEEE Expert 1991, 6, 16–30. [Google Scholar] [CrossRef]
  46. Xue, H.; Fu, H.; Xiao, L.; Fan, Y.; Zhao, D.; Dai, B. Traversability analysis for autonomous driving in complex environment: A LiDAR-based terrain modeling approach. J. Field Robot. 2023, 40, 1779–1803. [Google Scholar] [CrossRef]
  47. Triebel, R.; Pfaff, P.; Burgard, W. Multi-level surface maps for outdoor terrain mapping and loop closing. In Proceedings of the 2006 IEEE/RSJ International Conference on Intelligent Robots and Systems, Beijing, China, 9–15 October 2006; pp. 2276–2282. [Google Scholar]
  48. Hornung, A.; Wurm, K.M.; Bennewitz, M.; Stachniss, C.; Burgard, W. OctoMap: An efficient probabilistic 3D mapping framework based on octrees. Auton. Robot. 2013, 34, 189–206. [Google Scholar]
  49. Meagher, D. Geometric modeling using octree encoding. Comput. Graph. Image Process. 1982, 19, 129–147. [Google Scholar] [CrossRef]
  50. Laconte, J.; Debain, C.; Chapuis, R.; Pomerleau, F.; Aufrère, R. Lambda-field: A continuous counterpart of the bayesian occupancy grid for risk assessment. In Proceedings of the 2019 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Macau, China, 3–8 November 2019; pp. 167–172. [Google Scholar]
  51. Laconte, J.; Kasmi, A.; Pomerleau, F.; Chapuis, R.; Malaterre, L.; Debain, C.; Aufrère, R. A novel occupancy mapping framework for risk-aware path planning in unstructured environments. Sensors 2021, 21, 7562. [Google Scholar] [CrossRef] [PubMed]
  52. Randriamiarintsoa, E.; Laconte, J.; Thuilot, B.; Aufrère, R. Risk-Aware Navigation for Mobile Robots in Unknown 3D Environments. In Proceedings of the 2023 IEEE 26th International Conference on Intelligent Transportation Systems (ITSC), Bilbao, Spain, 24–28 September 2023. [Google Scholar]
  53. Benrabah, M.; Randriamiarintsoa, E.; Mousse, C.O.; Morceaux, J.; Aufrère, R.; Chapuis, R. Dual occupancy and knowledge maps management for optimal traversability risk analysis. In Proceedings of the 2023 26th International Conference on Information Fusion (FUSION), Charleston, SC, USA, 27–30 June 2023; pp. 1–6. [Google Scholar]
  54. Fan, D.D.; Agha-Mohammadi, A.A.; Theodorou, E.A. Learning risk-aware costmaps for traversability in challenging environments. IEEE Robot. Autom. Lett. 2021, 7, 279–286. [Google Scholar] [CrossRef]
  55. Cai, X.; Everett, M.; Sharma, L.; Osteen, P.R.; How, J.P. Probabilistic traversability model for risk-aware motion planning in off-road environments. In Proceedings of the 2023 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Detroit, MI, USA, 1–5 October 2023; pp. 11297–11304. [Google Scholar]
  56. Yang, Y.; Meng, X.; Yu, W.; Zhang, T.; Tan, J.; Boots, B. Learning semantics-aware locomotion skills from human demonstration. In Proceedings of the Conference on Robot Learning, Atlanta, GA, USA, 6–9 November 2023; pp. 2205–2214. [Google Scholar]
  57. Gupta, S.; Davidson, J.; Levine, S.; Sukthankar, R.; Malik, J. Cognitive mapping and planning for visual navigation. In Proceedings of the IEEE Conference on Computer Vision and Pattern Recognition, Honolulu, HI, USA, 21–26 July 2017; pp. 2616–2625. [Google Scholar]
  58. Silver, D.; Bagnell, J.A.; Stentz, A. Learning from demonstration for autonomous navigation in complex unstructured terrain. Int. J. Robot. Res. 2010, 29, 1565–1592. [Google Scholar] [CrossRef]
  59. Ratliff, N.D.; Silver, D.; Bagnell, J.A. Learning to search: Functional gradient techniques for imitation learning. Auton. Robot. 2009, 27, 25–53. [Google Scholar] [CrossRef]
  60. O’Callaghan, S.; Ramos, F.T.; Durrant-Whyte, H. Contextual occupancy maps using Gaussian processes. In Proceedings of the 2009 IEEE International Conference on Robotics and Automation, Kobe, Japan, 12–17 May 2009; pp. 1054–1060. [Google Scholar]
  61. Ramos, F.; Ott, L. Hilbert maps: Scalable continuous occupancy mapping with stochastic gradient descent. Int. J. Robot. Res. 2016, 35, 1717–1730. [Google Scholar] [CrossRef]
  62. Senanayake, R.; Ott, L.; O’Callaghan, S.; Ramos, F. Spatio-Temporal Hilbert Maps for Continuous Occupancy Representation in Dynamic Environments. In Proceedings of the 2016 Annual Conference on Neural Information Processing Systems (NIPS), Barcelona, Spain, 2016; pp. 3918–3926. [Google Scholar]
  63. Senanayake, R.; Ramos, F. Bayesian Hilbert Maps for Dynamic Continuous Occupancy Mapping. Conf. Robot Learn. 2017, 78, 458–471. [Google Scholar]
  64. Guizilini, V.; Senanayake, R.; Ramos, F. Dynamic hilbert maps: Real-time occupancy predictions in changing environments. In Proceedings of the 2019 International Conference on Robotics and Automation (ICRA), Montreal, QC, Canada, 20–24 May 2019; pp. 4091–4097. [Google Scholar]
  65. Li, Y.; Ruichek, Y. Occupancy grid mapping in urban environments from a moving on-board stereo-vision system. Sensors 2014, 14, 10454–10478. [Google Scholar] [CrossRef] [PubMed]
  66. Rohrmüller, F.; Althoff, M.; Wollherr, D.; Buss, M. Probabilistic mapping of dynamic obstacles using Markov Chains for replanning in dynamic environments. In Proceedings of the 2008 IEEE/RSJ International Conference on Intelligent Robots and Systems, Nice, France, 22–26 September 2008; pp. 2504–2510. [Google Scholar] [CrossRef]
  67. Chung, W.; Kim, S.; Choi, M.; Choi, J.; Kim, H.; Moon, C.B.; Song, J.B. Safe navigation of a mobile robot considering visibility of environment. IEEE Trans. Ind. Electron. 2009, 56, 3941–3950. [Google Scholar] [CrossRef]
  68. Damerow, F.; Eggert, J. Predictive risk maps. In Proceedings of the 2014 17th IEEE International Conference on Intelligent Transportation Systems, ITSC 2014, Qingdao, China, 8–11 October 2014; pp. 703–710. [Google Scholar] [CrossRef]
  69. Schreiber, M.; Belagiannis, V.; Glaeser, C.; Dietmayer, K. Motion Estimation in Occupancy Grid Maps in Stationary Settings Using Recurrent Neural Networks. In Proceedings of the 2020 IEEE International Conference on Robotics and Automation (ICRA), Paris, France, 31 May–31 August 2019. [Google Scholar]
  70. Hoermann, S.; Bach, M.; Dietmayer, K. Dynamic Occupancy Grid Prediction for Urban Autonomous Driving: A Deep Learning Approach with Fully Automatic Labeling. In Proceedings of the 2018 IEEE International Conference on Robotics and Automation (ICRA), Brisbane, Australia, 21–25 May 2018; pp. 2056–2063. [Google Scholar] [CrossRef]
  71. Nuss, D.; Reuter, S.; Thom, M.; Yuan, T.; Krehl, G.; Maile, M.; Gern, A.; Dietmayer, K. A random finite set approach for dynamic occupancy grid maps with real-time application. Int. J. Robot. Res. 2016, 37, 841–866. [Google Scholar] [CrossRef]
  72. Mouhagir, H.; Talj, R.; Cherfaoui, V.; Aioun, F.; Guillemard, F. Evidential-based approach for trajectory planning with tentacles, for autonomous vehicles. IEEE Trans. Intell. Transp. Syst. 2019, 21, 3485–3496. [Google Scholar] [CrossRef]
  73. Xiao, X.; Dufek, J.; Murphy, R.R. Robot risk-awareness by formal risk reasoning and planning. IEEE Robot. Autom. Lett. 2020, 5, 2856–2863. [Google Scholar] [CrossRef]
  74. Genevois, T.; Rummelhard, L.; Spalanzani, A.; Laugier, C. From Probabilistic Occupancy Grids to versatile Collision Avoidance using Predictive Collision Detection. In Proceedings of the ITSC 2023-IEEE International Conference on Intelligent Transportation Systems, Bilbao, Spain, 24–28 September 2023. [Google Scholar]
  75. LaChapelle, D.; Humphreys, T.; Narula, L.; Iannucci, P.; Moradi-Pari, E. Automotive collision risk estimation under cooperative sensing. In Proceedings of the ICASSP 2020—2020 IEEE International Conference on Acoustics, Speech and Signal Processing (ICASSP), Barcelona, Spain, 4–8 May 2020; pp. 9200–9204. [Google Scholar]
  76. Heiden, E.; Hausman, K.; Sukhatme, G.S.; Agha-mohammadi, A.A. Planning high-speed safe trajectories in confidence-rich maps. In Proceedings of the 2017 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS), Vancouver, BC, Canada, 24–28 September 2017; pp. 2880–2886. [Google Scholar]
  77. Slavík, A. Product Integration, Its History and Applications; Matfyzpress: Prague, Czech Republic, 2007. [Google Scholar]
  78. Ruszczyński, A. Risk-averse dynamic programming for Markov decision processes. Math. Program. 2010, 125, 235–261. [Google Scholar] [CrossRef]
  79. Majumdar, A.; Pavone, M. How should a robot assess risk? towards an axiomatic theory of risk in robotics. In Proceedings of the Robotics Research: The 18th International Symposium ISRR, Puerto Varas, Chile, 11–14 December 2017; pp. 75–84. [Google Scholar] [CrossRef]
  80. Barbosa, F.S.; Lacerda, B.; Duckworth, P.; Tumova, J.; Hawes, N. Risk-aware motion planning in partially known environments. In Proceedings of the 2021 60th IEEE Conference on Decision and Control (CDC), Austin, TX, USA, 14–17 December 2021; pp. 5220–5226. [Google Scholar]
  81. Kuindersma, S.R.; Grupen, R.A.; Barto, A.G. Variable risk control via stochastic optimization. Int. J. Robot. Res. 2013, 32, 806–825. [Google Scholar] [CrossRef]
  82. Rockafellar, R.T.; Uryasev, S. Optimization of conditional value-at-risk. J. Risk 2000, 2, 21–42. [Google Scholar] [CrossRef]
  83. Yang, X.; Gao, H.; Zhu, P.; Liu, C. Risk-Aware Motion Planning for Very-Large-Scale Robotics Systems Using Conditional Value-at-Risk. In Proceedings of the International Conference on Intelligent Robotics and Applications, Hangzhou, China, 5–7 July 2023; pp. 513–525. [Google Scholar]
  84. Ahmadi-Javid, A. Entropic value-at-risk: A new coherent risk measure. J. Optim. Theory Appl. 2012, 155, 1105–1123. [Google Scholar] [CrossRef]
  85. Dixit, A.; Ahmadi, M.; Burdick, J.W. Risk-sensitive motion planning using entropic value-at-risk. In Proceedings of the 2021 European Control Conference (ECC), Delft, The Netherlands, 29 June–2 July 2021; pp. 1726–1732. [Google Scholar]
  86. Ahmadi, M.; Rosolia, U.; Ingham, M.D.; Murray, R.M.; Ames, A.D. Risk-Averse Decision Making Under Uncertainty. IEEE Trans. Autom. Control 2023, 69, 55–68. [Google Scholar] [CrossRef]
  87. Cajas, D. Portfolio Optimization of Relativistic Value at Risk. 2023. Available online: https://www.researchgate.net/publication/369134014_Portfolio_Optimization_of_Relativistic_Value_at_Risk (accessed on 1 February 2024).
Figure 1. Autonomous ground vehicles applications. (a) self-driving cars; (b) military autonomous robot; (c) agricultural autonomous robot; and (d) the Mars rover.
Figure 1. Autonomous ground vehicles applications. (a) self-driving cars; (b) military autonomous robot; (c) agricultural autonomous robot; and (d) the Mars rover.
Sensors 24 01909 g001
Figure 2. Risk types with examples of robotic applications.
Figure 2. Risk types with examples of robotic applications.
Sensors 24 01909 g002
Figure 3. Three-dimensional representations of a tree scanned with a 3D LiDAR (from left to right): point cloud, elevation map, multi-level surface map, and octomap. From [48].
Figure 3. Three-dimensional representations of a tree scanned with a 3D LiDAR (from left to right): point cloud, elevation map, multi-level surface map, and octomap. From [48].
Sensors 24 01909 g003
Figure 4. Mapping of an unstructured grassed zone (a) using both a Bayesian occupancy grid (b) and the Lambda-field framework. (c) The robot, with its path in light blue, went around the nearest tree (circled in green) before going back to its initial position (the path in blue). From [51].
Figure 4. Mapping of an unstructured grassed zone (a) using both a Bayesian occupancy grid (b) and the Lambda-field framework. (c) The robot, with its path in light blue, went around the nearest tree (circled in green) before going back to its initial position (the path in blue). From [51].
Sensors 24 01909 g004
Figure 5. Example of an occupancy grid where the robot needs to cross and reach the goal in red, with two possible paths in blue and orange. From [50].
Figure 5. Example of an occupancy grid where the robot needs to cross and reach the goal in red, with two possible paths in blue and orange. From [50].
Sensors 24 01909 g005
Figure 6. The robots, which are represented as boxes with a filled triangle on the front, aim to navigate through an environment by following the dashed red line. The collision probability is uniform for the whole environment.
Figure 6. The robots, which are represented as boxes with a filled triangle on the front, aim to navigate through an environment by following the dashed red line. The collision probability is uniform for the whole environment.
Sensors 24 01909 g006
Figure 7. Example of risk assessments using Equation (4).
Figure 7. Example of risk assessments using Equation (4).
Sensors 24 01909 g007
Figure 8. Comparison of the mean, VaR, CVaR, and EVaR (obtained from [86]). The axes denote the values of risk c and its probability density function p ( c ) . The blue area denotes the ( 1 α ) % of the area under p ( c ) .
Figure 8. Comparison of the mean, VaR, CVaR, and EVaR (obtained from [86]). The axes denote the values of risk c and its probability density function p ( c ) . The blue area denotes the ( 1 α ) % of the area under p ( c ) .
Sensors 24 01909 g008
Table 1. Overview of the related surveys.
Table 1. Overview of the related surveys.
PaperYearDescriptionContribution
Sancho-Pradel and Gao [7]2010Planetary explorationA survey of the field from a planetary exploration perspective, bringing together the underlying techniques, existing approaches, and relevant applications under a common framework
Chhaniyara et al. [8]2012Planetary explorationBrought together vital information pertaining to various terrain characterization techniques into a single article
Papadakis [6]2013UniversalReviewed the field of 3D terrain traversability analysis by aggregating the diverse contributions from individual domains and elaborating on a number of key similarities, as well as differences
Guastella and Muscato [9]2020Unstructured EnvironmentsReviewed the contributions that adopted learning-based methods to solve the problem of environment perception and interpretation with the final aim of the autonomous context-aware navigation of ground vehicles in unstructured environments
Hu et al. [10]2020Obstacle detectionSummarized the considerations of the onboard multi-sensor configuration of intelligent ground vehicles in off-road environments
Borges et al. [11]2022UniversalReviewed the literature of terrain traversability analysis and defined unambiguous key terms, as well as discussed the links between the fundamental building blocks that range from terrain classification to traversability regression
Table 2. Overview of sensor-based approaches.
Table 2. Overview of sensor-based approaches.
ReferencesMethodTraversability RiskApplicationCriteria
[22]Instant goalMinimum distance to obstacleObstacle avoidanceObstacle
[23] μ NavMinimum distance to obstacleObstacle avoidanceObstacle
[24]Sliding surfaceBreach a set distance to obstacleObstacle avoidanceObstacle
[25,26,27]Chance constraintProbability of collisionObstacle avoidanceObstacle/Robot
[28,29]Proprioceptive sensingTerrain parametersOff-road navigationTerrain/Robot
[30]Exponential utility functionsUnspecified cost functionUniversalUnspecified
[32]Particle filteringParticle distributionNavigation under occlusionsObstacle
[31]Fuzzy rulesMembership to Fuzzy Traversability IndexOff-road navigationTerrain
[34]Quantile regressionUncertaintiesNavigation under occlusionsObstacle/Robot
Table 3. Overview of map-based approaches.
Table 3. Overview of map-based approaches.
ReferencesRisk CharacterizationMap DimensionsPaper Application
[35]Probability of occupancy2DUniversal
[36]Probability of traversability2DOff-road navigation
[37]Slope, curvature, and roughness2.5DOff-road navigation
[38]Binary classification2DOff-road navigation
[39]Object density2DOff-road navigation
[41]Degree of membership to fuzzy sets2DOff-road navigation
[44,45]Elevation2.5DUniversal
[47]Elevation2.5DEnvironments with vertical structures
[48,49]Probability of occupancy3DUniversal
[50,52]Rate of a harmful event2DOff-road navigation
[54]CVaR of unspecified variable2DOff-road navigation
[55]Traction distribution2DOff-road navigation
[56]Speed2DOff-road navigation
[58]Generalizable traversability cost2DComplex unstructured terrain
[60]Gaussian distribution2D/3DUrban environment
[61]Probability of occupancy2D/3DUrban environment
Table 4. Coherence of the mentioned risk metrics.
Table 4. Coherence of the mentioned risk metrics.
MetricAxioms [79]Coherence
Expected ValueA1–A6Coherent
Worst CaseA1–A6Coherent
Mean VarianceA6Non-coherent
Value at Risk (VaR)A1–A3, A5, A6Non-coherent
Conditional Value at Risk (CVaR)A1–A6Coherent
Entropic Value at Risk (EVaR)A1–A6Coherent
Relativistic Value at Risk (RLVaR)A1–A6Coherent
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

Benrabah, M.; Orou Mousse, C.; Randriamiarintsoa, E.; Chapuis, R.; Aufrère, R. A Review on Traversability Risk Assessments for Autonomous Ground Vehicles: Methods and Metrics. Sensors 2024, 24, 1909. https://doi.org/10.3390/s24061909

AMA Style

Benrabah M, Orou Mousse C, Randriamiarintsoa E, Chapuis R, Aufrère R. A Review on Traversability Risk Assessments for Autonomous Ground Vehicles: Methods and Metrics. Sensors. 2024; 24(6):1909. https://doi.org/10.3390/s24061909

Chicago/Turabian Style

Benrabah, Mohamed, Charifou Orou Mousse, Elie Randriamiarintsoa, Roland Chapuis, and Romuald Aufrère. 2024. "A Review on Traversability Risk Assessments for Autonomous Ground Vehicles: Methods and Metrics" Sensors 24, no. 6: 1909. https://doi.org/10.3390/s24061909

Note that from the first issue of 2016, this journal uses article numbers instead of page numbers. See further details here.

Article Metrics

Back to TopTop