Occupancy Grid Mapping

9 minute read ·

Published:

Besides state estimation or localization, which provide a robot with knowledge of where it is, it’s equally important for a mobile robot to perceive its surrounding and form a knowledge of where is occupied, that’s where mapping comes in. This note covers a fundamental mapping algorithm, occupancy grid mapping.

Problem Statement

In occupancy grid mapping, a map m={mi}i=1N\mathbf{m}=\left\{m_i\right\}_{i=1}^N is discretized into NN different cells, where each cell mim_i is a binary random variable that models the occupancy, and p(mi)p(m_i) is the probability of a cell being occupied. The map is assumed to be static. The goal is to find the belief belt(m)=p(mz1:t,x1:t)\mathrm{bel}_t(\mathbf{m})=p(\mathbf{m}\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t}), where z\mathbf{z} is the observation and x\mathbf{x} is the state of the robot.

Two assumptions are made for tractability

  • The robot state xt\mathbf{x}_t are known.
  • The occupancy of individual cells mim_i are independent, and thus
belt(m)=p(mz1:t,x1:t)=i=1Np(miz1:t,x1:t)\begin{equation} \mathrm{bel}_t(\mathbf{m})=p(\mathbf{m}\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})=\prod_{i=1}^{N}p(m_i\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t}) \end{equation}

At each timestep tt, the sensor performs some measurement and provide the information of whether a cell mim_i is believed to be occupied or not, in terms of p(mizt,xt)p(m_i\mid\mathbf{z}_t, \mathbf{x}_t), which is known as the inverse sensor model.

Inverse sensor model of a laser beam range sensor, image taken from [1]

One simple inverse sensor model is shown in the figure above. Consider a laser beam range sensor that provides the reading z=(z1r,,znr,z1ϕ,,znϕ)\mathbf{z}=(z_1^r,\dots, z_n^r,z_{1}^{\phi},\dots,z_{n}^{\phi}), where zkrz_k^r and zkϕz_k^\phi are the range and bearing of the kk-th beam. For grid ii, let rir_i and ϕi\phi_i be the range and bearing of the grid as observed from the current robot pose x\mathbf{x}, and k=arg minjϕizjϕk=\argmin_j\left|\phi_i-z_j^{\phi}\right| be the beam going through that gird. Based on the relation of a grid’s position relative to the robot, we have three different cases:

  • If ri>min(zmax,zkr+wgrid)r_i>\min(z_{\max},z_k^r+w_{\mathrm{grid}}) or ϕizkϕ>wbeam/2\left|\phi_i-z_{k}^{\phi}\right|>w_{\mathrm{beam}} / 2, then return ppreviousp_{\mathrm{previous}}, the sensor has no information about this grid.
  • Else if zkr<zmaxz_k^r < z_{\max} and rizkr<wgrid\left|r_i-z_k^r\right|<w_{\mathrm{grid}}, then return poccupiedp_{\mathrm{occupied}}, the sensor think the grid is occupied.
  • Else if zkr<zmaxz_k^r<z_{\max} and ri<zkrr_i < z_k^r, then return pfreep_{\mathrm{free}}, the sensor think the grid is free.

where zmaxz_{\max} is a sensor-specific parameter representing the maximum detectable range, wgridw_{\mathrm{grid}} is the grid size and wbeamw_{\mathrm{beam}} is the width of each beam.

Mapping Algorithm

Following the Bayes filtering framework, a general algorithm can be derived for the occupancy grid mapping [2]. Starting from equation 1,

p(miz1:t,x1:t)=p(ztmi,z1:t1,x1:t)p(miz1:t1,x1:t)p(ztz1:t1,x1:t)(Bayes rule)=p(ztmi,xt)p(miz1:t1,x1:t1)p(ztz1:t1,x1:t)(Markov assumption)=p(mizt,xt)p(ztxt)p(miz1:t1,x1:t1)p(mixt)p(ztz1:t1,x1:t)(Bayes rule)\begin{align*} p(m_i\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})&=\frac{p(\mathbf{z}_t\mid m_i, \mathbf{z}_{1:t-1},\mathbf{x}_{1:t})p(m_i\mid\mathbf{z}_{1:t-1}, x_{1:t})}{p(\mathbf{z}_t\mid\mathbf{z}_{1:t-1},\mathbf{x}_{1:t})} && \text{(Bayes rule)}\\ &=\frac{p(\mathbf{z}_t\mid m_i, \mathbf{x}_t)p(m_i\mid\mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})}{p(\mathbf{z}_t\mid\mathbf{z}_{1:t-1},\mathbf{x}_{1:t})} && \text{(Markov assumption)}\\ &=\frac{p(m_i \mid \mathbf{z}_t, \mathbf{x}_t) \, p(\mathbf{z}_t \mid \mathbf{x}_t) \, p(m_i \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})}{p(m_i \mid \mathbf{x}_t) \, p(\mathbf{z}_t \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t})} && \text{(Bayes rule)} \end{align*}

Further notice that the map m\mathbf{m} is independent of the robot state xt\mathbf{x}_t, we obtain

p(miz1:t,x1:t)=p(mizt,xt)p(ztxt)p(miz1:t1,x1:t1)p(mi)p(ztz1:t1,x1:t)\begin{equation} p(m_i\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})=\frac{p(m_i \mid \mathbf{z}_t, \mathbf{x}_t) \, p(\mathbf{z}_t \mid \mathbf{x}_t) \, p(m_i \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})}{p(m_i) \, p(\mathbf{z}_t \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t})} \end{equation}

Similarly, for the negation

p(¬miz1:t,x1:t)=p(¬mizt,xt)p(ztxt)p(¬miz1:t1,x1:t1)p(¬mi)p(ztz1:t1,x1:t)\begin{equation} p(\lnot m_i\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})= \frac{p(\lnot m_i \mid \mathbf{z}_t, \mathbf{x}_t) \, p(\mathbf{z}_t \mid \mathbf{x}_t) \, p(\lnot m_i \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})}{p(\lnot m_i) \, p(\mathbf{z}_t \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t})} \end{equation}

Compute the ratio of equation (2) and (3), we get

p(miz1:t,x1:t)1p(miz1:t,x1:t)=p(mizt,xt)p(miz1:t1,x1:t1)p(¬mi)p(¬mizt,xt)p(¬miz1:t1,x1:t1)p(mi)=p(mizt,xt)1p(mizt,xt)inverse sensor modelp(miz1:t1,x1:t1)1p(miz1:t1,x1:t1)recursive term1p(mi)p(mi)prior\begin{align*} \frac{p(m_i \mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})}{1 - p(m_i \mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})}&= \frac{p(m_i \mid \mathbf{z}_t, \mathbf{x}_t) \, p(m_i \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1}) \, p(\neg m_i)}{p(\neg m_i \mid \mathbf{z}_t, \mathbf{x}_t) \, p(\neg m_i \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1}) \, p(m_i)}\\ &= \underbrace{\frac{p(m_i \mid \mathbf{z}_t, \mathbf{x}_t)}{1 - p(m_i \mid \mathbf{z}_t, \mathbf{x}_t)}}_{\text{inverse sensor model}} \underbrace{\frac{p(m_i \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})}{1 - p(m_i \mid \mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})}}_{\text{recursive term}} \underbrace{\frac{1 - p(m_i)}{p(m_i)}}_{\text{prior}} \end{align*}

Then, change to log odds form by defining

l(x)logp(x)1p(x)l(x)\triangleq\log\frac{p(x)}{1-p(x)}

and the product chain turns into a sum

l(miz1:t,x1:t)=l(mizt,xt)+l(miz1:t1,x1:t1)l(mi)l(m_i\mid\mathbf{z}_{1:t}, \mathbf{x}_{1:t})=l(m_i\mid \mathbf{z}_{t},\mathbf{x}_t)+l(m_i\mid\mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})-l(m_i)

Bayes Inference using Conjugate Prior

The previous section derived an equation for updating the belief of the map under the Bayes framework, however, it lacks the notion of uncertainty (i.e., how confident we are about the map). With the notion of conjugate prior, a proper selection of the underlying distribution function for p(mi)p(m_i) can both simplifies the updating rule and provide a closed form formula for uncertainty.

Recall that from Bayes rule

p(miz1:t,x1:t)posteriorp(ztmi,xt)likelihoodp(miz1:t1,x1:t1)prior\begin{equation*} \underbrace{p(m_i\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})}_{\text{posterior}}\propto\underbrace{p(\mathbf{z}_t\mid m_i, \mathbf{x}_t)}_{\text{likelihood}}\cdot\underbrace{p(m_i\mid\mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})}_{\text{prior}} \end{equation*}

Bernoulli Likelihood and Beta Prior

First consider the case where the occupancy of a grid is binary, i.e., mi{0,1}m_i\in\{0, 1\}. Let θip(mi=1)\theta_i\triangleq p(m_i=1) be the unknown occupancy probability. From the inverse sensor model described above, we know that each sensor measurement provide a binary result, denoted as yty_t, where

yt={1,if the inverse sensor model return poccupied0,if the inverse sensor model return pfree\begin{equation*} y_t=\left\{\begin{matrix} 1, & \text{if the inverse sensor model return }p_{\text{occupied}}\\ 0, & \text{if the inverse sensor model return }p_{\text{free}} \end{matrix}\right. \end{equation*}

Then, the likelihood is modeled as a Bernoulli with parameter θi\theta_i, i.e.,

p(ztmi,xt)p(ytθi)=θiyt(1θi)1ytp(\mathbf{z}_t\mid m_i, \mathbf{x}_t)\propto p(y_t\mid \theta_i)=\theta_i^{y_t}\left(1-\theta_i\right)^{1-y_t}

Furthermore, if we model the prior as a Beta distribution, i.e.,

p(θiz1:t1,x1:t1)=Beta(θi;αi,t1,βi,t1)=1B(αi,t1,βi,t1)θiαi,t11(1θi)βi,t11p(\theta_i\mid \mathbf{z}_{1:t-1},\mathbf{x}_{1:t-1})=\mathrm{Beta}(\theta_i;\alpha_{i,t-1},\beta_{i,t-1})=\frac{1}{B(\alpha_{i,t-1}, \beta_{i,t-1})}\theta_i^{\alpha_{i,t-1} -1}\left(1-\theta_i\right)^{\beta_{i,t-1} - 1}

where B(,)B(\cdot, \cdot) is the beta function.

Then, it follows from the Bayes rule that the posterior is

p(θiz1:t,x1:t)p(ytθi)p(θiz1:t1,x1:t1)θiyt(1θi)1ytθiαi,t11(1θi)βi,t11=θi(αi,t1+yt)1(1θi)(βi,t1+1yt)1\begin{align*} p(\theta_i\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})&\propto p(y_t\mid \theta_i)\cdot p(\theta_i\mid\mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})\\ &\propto\theta_i^{y_t}\left(1-\theta_i\right)^{1-y_t}\cdot \theta_i^{\alpha_{i,t-1} -1}\left(1-\theta_i\right)^{\beta_{i,t-1} - 1}\\ &=\theta_i^{(\alpha_{i,t-1}+y_t)-1}\left(1-\theta_i\right)^{(\beta_{i,t-1}+1-y_t)-1} \end{align*}

which still follows a Beta distribution, p(θiz1:t,x1:t)=Beta(θi;αt,βt)p(\theta_i\mid \mathbf{z}_{1:t},\mathbf{x}_{1:t})=\mathrm{Beta}(\theta_i;\alpha_t, \beta_t), where

αi,t=αi,t1+ytandβi,t=βi,t1+(1yt)\begin{align} \alpha_{i,t}=\alpha_{i,t-1}+y_t &&\text{and}&& \beta_{i,t} = \beta_{i,t-1}+(1-y_t) \end{align}

In this case, we call beta distribution the conjugate prior for the Bernoulli likelihood.

  • Conjugate Distribution and Conjugate Prior [2]
    • If the posterior distributions are in the same probability distribution family as the prior probability distribution, the prior and posterior are then called conjugate distributions.
    • The prior is called a conjugate prior for the likelihood function.

Note that the choice of modeling the prior as a Beta distribution here is an algebraic convenience, which provides a closed-form expression for the posterior. Then the mean and covariance can be easily obtained

E[θi]=αiαi+βiandV[θi]=αiβi(αi+βi)2(αi+βi+1)\begin{align*} \mathbb{E}[\theta_i]=\frac{\alpha_i}{\alpha_i + \beta_i} && \text{and} && \mathbb{V}[\theta_i]=\frac{\alpha_i\beta_i}{\left(\alpha_i+\beta_i\right)^2\left(\alpha_i+\beta_i+1\right)} \end{align*}

Given the simple update rule in Equation (4), the recursive Bayes framework becomes a simple counting problem: when the sensor model returns “occupied”, increment αi\alpha_i by 1, if the sensor model returns “free”, increment βi\beta_i by 1.

Categorical Likelihood and Dirichlet Prior

Next, we can generalize the above binary occupancy mapping into a multi-categorical case using the categorical likelihood and the Dirichlet prior.

Suppose we have KK different categories and each grid can be belongs to exactly one category or empty, i.e., mi{0,1,,K}m_i\in\{0,1,\dots, K\}. Let θi=(θi,0,,θi,K)\boldsymbol{\theta}_i=\left(\theta_{i,0},\dots, \theta_{i, K}\right) be a vector where θi,kp(mi=k)\theta_{i,k}\triangleq p(m_i=k), and k=0Kθi,k=1\sum_{k=0}^{K}\theta_{i,k}=1. Further let the measurement be a one-hot-encoded tuple yt=(yt,0,yt,1,,yt,K)\mathbf{y}_t=(y_{t,0},y_{t, 1}, \dots, y_{t,K}) with yt,k{0,1}y_{t,k}\in\{0, 1\} and k=0Kyt,k=1\sum_{k=0}^{K}y_{t,k}=1, indicating which category the sensor believes cell ii belongs to.

Similarly, the likelihood can be modeled as a categorical distribution

p(ztmi,xt)p(ytθi)=k=0Kθi,kyt,kp(\mathbf{z}_t\mid m_i, \mathbf{x}_t)\propto p(\mathbf{y}_t\mid \boldsymbol{\theta}_i)=\prod_{k=0}^{K}\theta_{i,k}^{y_{t,k}}

Then, we apply a Dirichlet distribution with parameter αi,t1=(αi,t1,0,,αi,t1,K)\boldsymbol{\alpha}_{i,t-1}=(\alpha_{i,t-1,0}, \dots, \alpha_{i,t-1,K}) on the prior

p(θiz1:t1,x1:t1)=Dir(θi;αi,t1)=1B(αi,t1)k=0Kθi,kαi,t1,k1p(\boldsymbol{\theta}_i\mid \mathbf{z}_{1:t-1},\mathbf{x}_{1:t-1})=\mathrm{Dir}(\boldsymbol{\theta}_i;\boldsymbol{\alpha}_{i,t-1})=\frac{1}{B(\boldsymbol{\alpha}_{i,t-1})}\prod_{k=0}^{K}\theta_{i,k}^{\alpha_{i,t-1,k}-1}

The posterior then follows another Dirichlet distribution with parameter αi,t\boldsymbol{\alpha}_{i,t},

p(θiz1:t,x1:t)p(ytθi)p(θiz1:t1,x1:t1)k=0Kθi,kyt,kk=0Kθi,kαi,t1,k1=k=0Kθi,kαi,t1,k+yt,k1\begin{align*} p(\theta_i\mid \mathbf{z}_{1:t}, \mathbf{x}_{1:t})&\propto p(\mathbf{y}_t\mid \boldsymbol{\theta}_i)\cdot p(\boldsymbol{\theta}_i\mid\mathbf{z}_{1:t-1}, \mathbf{x}_{1:t-1})\\ &\propto\prod_{k=0}^{K}\theta_{i,k}^{y_{t,k}}\cdot\prod_{k=0}^{K}\theta_{i,k}^{\alpha_{i,t-1,k}-1}\\ &=\prod_{k=0}^{K}\theta_{i,k}^{\alpha_{i,t-1,k}+y_{t,k}-1} \end{align*}

Thus, the update rule is

αi,t,k=αi,t1,k+yt,k\begin{equation} \alpha_{i,t,k}=\alpha_{i,t-1,k}+y_{t,k} \end{equation}

which is simply adding 1 to the α\alpha of the category to which the sensor believes the cell belongs.

For the multi-categorical case, the mean and covariance can also be computed in closed-form:

E[θi,k]=αi,kk=0Kαi,kandV[θi,k]=αi,k(k=0Kαi,kαi,k)(k=0Kαi,k)2(k=0Kαi,k1)\begin{align*} \mathbb{E}[\theta_{i,k}]=\frac{\alpha_{i,k}}{\sum_{k=0}^{K}\alpha_{i,k}} && \text{and} && \mathbb{V}[\theta_{i,k}]=\frac{\alpha_{i,k}\left(\sum_{k=0}^{K}\alpha_{i,k}-\alpha_{i,k}\right)}{\left(\sum_{k=0}^{K}\alpha_{i,k}\right)^2\left(\sum_{k=0}^{K}\alpha_{i,k}-1\right)} \end{align*}

Counting Sensor Models

Finally, we can write out the mapping algorithm for multi-category discrete counting sensor model

Algorithm: multi_category_discrete_CSM(mi,z,αi)Input: mi=(ri,ϕi) range and bearing of the grid from robot pose x;  z=(z1r,,znr,z1ϕ,,znϕ,z1c,,znc) range, bearing, and category label,  where zjc{1,,K} is the semantic class detected by beam j;  αi=(αi,0,αi,1,,αi,K) for cell i, where category 0 denotes free.Output: updated αi.1.b=argminjϕizjϕ(Find the beam going through cell mi)2.If ri>min ⁣(zmax,zbr+wgrid) or ϕizbϕ>wbeam/23.pass(Outside of the perception field)4.Else If zbr<zmax and rizbr<wgrid5.αi,zbcαi,zbc+1(Update: cell belongs to categoryzbc)6.Else If zbr<zmax and ri<zbr7.αi,0αi,0+1(Update free space (category 0))\begin{align*}& \textbf{Algorithm: } \texttt{multi\_category\_discrete\_CSM}(m_i, \mathbf{z}, \boldsymbol{\alpha}_i) \\& \textbf{Input: } m_i = (r_i, \phi_i) \text{ range and bearing of the grid from robot pose } \mathbf{x}\text{;} \\& \quad\quad\quad\; \mathbf{z} = (z_1^r, \dots, z_n^r,\, z_1^\phi, \dots, z_n^\phi,\, z_1^c, \dots, z_n^c) \text{ range, bearing, and category label,} \\& \quad\quad\quad\; \text{where } z_j^c \in \{1, \dots, K\} \text{ is the semantic class detected by beam } j\text{;} \\& \quad\quad\quad\; \boldsymbol{\alpha}_i = (\alpha_{i,0},\, \alpha_{i,1},\, \dots,\, \alpha_{i,K}) \text{ for cell } i\text{, where category } 0 \text{ denotes free.} \\& \textbf{Output: } \text{updated } \boldsymbol{\alpha}_i. \\[6pt]& 1. \quad b = \arg\min_j\left|\phi_i - z_j^{\phi}\right|\,\, (\text{Find the beam going through cell } m_i) \\& 2. \quad \textbf{If } r_i > \min\!\big(z_{\max},\, z_b^r + w_{\mathrm{grid}}\big) \text{ or } \left|\phi_i - z_b^{\phi}\right| > w_{\mathrm{beam}} / 2 \\& 3. \quad \quad \textbf{pass} \,\,(\text{Outside of the perception field}) \\& 4. \quad \textbf{Else If } z_b^r < z_{\max} \text{ and } \left|r_i - z_b^r\right| < w_{\mathrm{grid}} \\& 5. \quad \quad \alpha_{i,\, z_b^c} \leftarrow \alpha_{i,\, z_b^c} + 1 \,\, (\text{Update: cell belongs to category} z_b^c) \\& 6. \quad \textbf{Else If } z_b^r < z_{\max} \text{ and } r_i < z_b^r \\& 7. \quad \quad \alpha_{i,\, 0} \leftarrow \alpha_{i,\, 0} + 1 \,\,(\text{Update free space (category 0)}) \end{align*}

Note that if K=1K=1, the above algorithm reduces to the binary occupancy grid mapping.

One more generalization can be made to the above discrete CSM, which is to take into account the spatial continuity. In the multi_category_discrete_CSM\texttt{multi\_category\_discrete\_CSM} algorithm listed above, an observation falling into a cell grid ii only updates αi\boldsymbol{\alpha}_i of that cell and not any other cell. In reality, if a cell is observed to be occupied by a wall, then its nearby cells may also be occupied by that wall.

Let XRd\mathcal{X}\subset\mathbb{R}^d be the spatial support of the map (e.g., d=2d=2 or d=3d=3). Define a kernel function k(,):X×X[0,1]k(\cdot,\cdot):\mathcal{X}\times\mathcal{X}\to[0,1] that operates on the spatial inputs. The kernel function determines how much an observation at a location influences our belief about location x\mathbf{x}^{*}.

Specifically, the inverse sensor model is corrected as follows. For beam kk, we construct a set of sample points S={xobs,xray(1),xray(2),}\mathcal{S}=\left\{\mathbf{x}_{\mathrm{obs}},\mathbf{x}_{\mathrm{ray}}^{(1)}, \mathbf{x}_{\mathrm{ray}}^{(2)}, \dots\right\} where

  • xobsRd\mathbf{x}_{\mathrm{obs}}\in\mathbb{R}^d is the global coordinate of the beam’s endpoint. All grids close to this endpoint is considered as occupied (or fall into some category), by a kernel-weighted factor.
  • xray(l)Rd\mathbf{x}_{\mathrm{ray}}^{(l)}\in\mathbb{R}^{d} is the global coordinate of other sample points on the beam. All grids close to any of these sample points are considered as free, by a kernel-weighted factor.

Then, during the map construction, we update the Dirichlet parameter for grid ii with

αi,t,k=αi,t1,k+xSk(x,xi)yt,k\begin{equation} \alpha_{i,t,k}=\alpha_{i,t-1,k}+\sum_{\mathbf{x}^*\in\mathcal{S}}k(\mathbf{x}^*, \mathbf{x}_{i})y_{t,k} \end{equation}

Another benefit of continuous CSM is that we can query any point x\mathbf{x}^* in the spatial support after the map is built, with

αk(x)=αk,0+tk(x,xt)yt,k\alpha_k(\mathbf{x}^*)=\alpha_{k,0}+\sum_{t}k(\mathbf{x}^*,\mathbf{x}_t)y_{t,k}

where αk,0\alpha_{k,0} is the initial prior.

Reference

[2]. M. Ghaffari, ROB530 Lecture Slides — Robotic Mapping. University of Michigan, 2026.

Categories: Robotics