зеркало из https://github.com/microsoft/AirSim.git
Fixes per review
This commit is contained in:
Родитель
1af0a4e242
Коммит
09cf5acae5
|
@ -1,7 +1,7 @@
|
|||
AirSim provides a Python-based event camera simulator, aimed at performance and ability to run in real-time along with the sim.
|
||||
|
||||
#### Event cameras
|
||||
An event camera is a special vision sensor that measures changes in logarithmic brightness and only reports 'events', i.e., a set of bytes every time the absolute change exceeds a certain threshold. The event camera only reports the timestamp of the measurement, pixel location and the polarity: which is a +1/-1 based on whether the logarithmic brightness increased or decreased. Most event cameras have a temporal resolution of the order of microseconds, making them significantly faster than RGB sensors, and also demonstrate a high dynamic range and low motion blur. More details about event cameras can be found in [this tutorial from RPG-UZH](http://rpg.ifi.uzh.ch/docs/scaramuzza/Tutorial_on_Event_Cameras_Scaramuzza.pdf)
|
||||
An event camera is a special vision sensor that measures changes in logarithmic brightness and only reports 'events'. Each event is a set of four values that gets generated every time the absolute change in the logarithmic brightness exceeds a certain threshold. An event contains the timestamp of the measurement, pixel location (x and y coordinates) and the polarity: which is either +1/-1 based on whether the logarithmic brightness has increased or decreased. Most event cameras have a temporal resolution of the order of microseconds, making them significantly faster than RGB sensors, and also demonstrate a high dynamic range and low motion blur. More details about event cameras can be found in [this tutorial from RPG-UZH](http://rpg.ifi.uzh.ch/docs/scaramuzza/Tutorial_on_Event_Cameras_Scaramuzza.pdf)
|
||||
|
||||
#### AirSim event simulator
|
||||
|
||||
|
@ -14,7 +14,15 @@ x and y are the pixel locations of the event firing, timestamp is the global tim
|
|||
![image](images/event_sim.png)
|
||||
|
||||
#### Usage
|
||||
An example script to run the event simulator alongside AirSim is located at https://github.com/microsoft/AirSim/blob/master/PythonClient/eventcamera_sim/test_event_sim.py. The implementation of the actual event simulation, written in Python and numba, is at https://github.com/microsoft/AirSim/blob/master/PythonClient/eventcamera_sim/event_simulator.py. The event simulator is initialized as follows, with the arguments controlling the resolution of the camera.
|
||||
An example script to run the event simulator alongside AirSim is located at https://github.com/microsoft/AirSim/blob/master/PythonClient/eventcamera_sim/test_event_sim.py. The following optional command-line arguments can be passed to this script.
|
||||
|
||||
```
|
||||
args.width, args.height (float): Simulated event camera resolution
|
||||
args.save (bool): Whether or not to save the event data to a file, args.debug (bool): Whether or not to display the simulated events as an image
|
||||
```
|
||||
|
||||
|
||||
The implementation of the actual event simulation, written in Python and numba, is at https://github.com/microsoft/AirSim/blob/master/PythonClient/eventcamera_sim/event_simulator.py. The event simulator is initialized as follows, with the arguments controlling the resolution of the camera.
|
||||
|
||||
```
|
||||
from event_simulator import *
|
||||
|
@ -26,7 +34,7 @@ The actual computation of the events is triggered through a callback function, w
|
|||
```
|
||||
event_img, events = ev_sim.image_callback(img, ts_delta)
|
||||
```
|
||||
The callback returns an event image as a one dimensional array of +1/-1 values, thus indicating only whether events were seen at each pixel, but not the timing/number of events. This one dimensional array can be converted into the red/blue event image as seen in the function `convert_event_img_rgb`. `events` is a numpy array of events, each of format `<x> <y> <timestamp> <pol>`.
|
||||
This function, which behaves similar to a callback (called every time a new image is received) returns an event image as a one dimensional array of +1/-1 values, thus indicating only whether events were seen at each pixel, but not the timing/number of events. This one dimensional array can be converted into the red/blue event image as seen in the function `convert_event_img_rgb`. `events` is a numpy array of events, each of format `<x> <y> <timestamp> <pol>`.
|
||||
|
||||
Through the callback, the event sim computes the difference between the past and the current image, and computes a stream of events which is then returned as a numpy array. This can then be appended to a file.
|
||||
|
||||
|
|
|
@ -1,9 +1,9 @@
|
|||
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:
|
||||
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 from Python is of the structure:
|
||||
|
||||
```
|
||||
createVoxelGrid(self, position, x, y, z, res, of)
|
||||
simCreateVoxelGrid(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
|
||||
|
@ -34,7 +34,7 @@ for (float i = 0; i < ncells_x; i++) {
|
|||
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.
|
||||
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. One nifty little utility to visualize a created binvox files is [viewvox](https://www.patrickmin.com/viewvox/). Similarly, `binvox2bt` can convert the binvox to an octomap file.
|
||||
|
||||
##### Example voxel grid in Blocks:
|
||||
![image](images/voxel_grid.png)
|
||||
|
@ -42,13 +42,13 @@ The voxel grids are stored in the binvox format which can then be converted by t
|
|||
##### Blocks voxel grid converted to Octomap format (visualized in rviz):
|
||||
![image](images/octomap.png)
|
||||
|
||||
The Blocks voxel grid can be constructed through the following example script:
|
||||
As an example, a voxel grid can be constructed as follows, once the Blocks environment is up and running:
|
||||
|
||||
```
|
||||
import airsim
|
||||
c = airsim.VehicleClient()
|
||||
center = airsim.Vector3r(0, 0, 0)
|
||||
output_path = "~/map.binvox"
|
||||
output_path = os.path.join(os.getcwd(), "map.binvox")
|
||||
c.simCreateVoxelGrid(center, 100, 100, 100, 0.5, output_path)
|
||||
```
|
||||
|
||||
|
|
Загрузка…
Ссылка в новой задаче