Skip to content

Commit

Permalink
Voxel grid documentation
Browse files Browse the repository at this point in the history
  • Loading branch information
saihv committed Dec 22, 2020
1 parent 77d619f commit 729ff25
Showing 1 changed file with 40 additions and 0 deletions.
40 changes: 40 additions & 0 deletions docs/voxel_grid.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
AirSim provides a feature that constructs ground truth voxel grids of the world directly from Unreal Engine. A voxel grid is a representation of the occupancy of a given world/map, by discretizing into cells of a certain size; and recording a voxel if that particular location is occupied.

The logic for constructing the voxel grid is in WorldSimApi.cpp->createVoxelGrid(). For now, the assumption is that the voxel grid is a cube - and the API call is of the structure:

```
createVoxelGrid(self, position, x, y, z, res, of)
position (Vector3r): Global position around which voxel grid is centered in m
x, y, z (float): Size of each voxel grid dimension in m
res (float): Resolution of voxel grid in m
of (str): Name of output file to save voxel grid as
```

Within `createVoxelGrid()`, the main Unreal Engine function that returns occupancy is [OverlapBlockingTestByChannel](https://docs.unrealengine.com/en-US/API/Runtime/Engine/Engine/UWorld/OverlapBlockingTestByChannel/index.html).

```
OverlapBlockingTestByChannel(position, rotation, ECollisionChannel, FCollisionShape, params);
```

This function is called on the positions of all the 'cells' we wish to discretize the map into, and the returned occupancy result is collected into an array `voxel_grid_`. The indexing of the cell occupancy values follows the convention of the [binvox](https://www.patrickmin.com/binvox/binvox.html) format.

```
for (float i = 0; i < ncells_x; i++) {
for (float k = 0; k < ncells_z; k++) {
for (float j = 0; j < ncells_y; j++) {
int idx = i + ncells_x * (k + ncells_z * j);
FVector position = FVector((i - ncells_x /2) * scale_cm, (j - ncells_y /2) * scale_cm, (k - ncells_z /2) * scale_cm) + position_in_UE_frame;
voxel_grid_[idx] = simmode_->GetWorld()->OverlapBlockingTestByChannel(position, FQuat::Identity, ECollisionChannel::ECC_Pawn, FCollisionShape::MakeBox(FVector(scale_cm /2)), params);
}
}
}
```

The occupancy of the map is calculated iteratively over all discretized cells, which can make it an intensive operation depending on the resolution of the cells, and the total size of the area being measured. If the user's map of interest does not change much, it is possible to run the voxel grid operation once on this map, and save the voxel grid and reuse it. For performance, or with dynamic environments, we recommend running the voxel grid generation for a small area around the robot; and subsequently use it for local planning purposes.


The voxel grids are stored in the binvox format which can then be converted by the user into an octomap .bt or any other relevant, desired format. Subsequently, these voxel grids/octomaps can be used within mapping/planning. [viewvox](https://www.patrickmin.com/viewvox/) is a nifty little utility to then visualize the created binvox file. Similarly, `binvox2bt` can convert the binvox to an octomap file.

##### Example voxel grid in Blocks:
![image](https://user-images.githubusercontent.com/2274262/101970694-c7755280-3be0-11eb-886c-74f05c839478.png)

1 comment on commit 729ff25

@p00uya
Copy link

@p00uya p00uya commented on 729ff25 May 31, 2021

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I can't find which part of the code should be run?

Please sign in to comment.