3.5 Camera
Derived from Device.
Camera { |
3.5.1 Description
The Camera node is used to model a robot's on-board camera, a range-finder, or both simultaneously. The resulted image can be displayed on the 3D window. Depending on its setup, the Camera node can model a linear camera, a lidar device, a Microsoft Kinect or even a biological eye which is spherically distorted.
3.5.2 Field Summary
-
fieldOfView: horizontal field of view angle of the camera. The value ranges from 0 to π radians. Since camera pixels are squares, the vertical field of view can be computed from the width, height and horizontal fieldOfView:
vertical FOV = fieldOfView * height / width
-
width: width of the image in pixels
-
height: height of the image in pixels
-
type: type of the camera: "color", "range-finder" or "both". The camera types are described precisely in the corresponding subsection below.
-
spherical: switch between a planar or a spherical projection. A spherical projection can be used for example to simulate a biological eye or a lidar device. More information on spherical projection in the corresponding subsection below.
-
The near field defines the distance from the camera to the near clipping plane. This plane is parallel to the camera retina (i.e. projection plane). The near field determines the precision of the OpenGL depth buffer. A too small value produces depth fighting between overlaid polygons, resulting in random polygon overlaps. More information on frustums in the corresponding subsection below.
-
The maxRange field is used only when the camera is a range-finder. In this case, maxRange defines the distance between the camera and the far clipping plane. The far clipping plane is not set to infinity. This field defines the maximum range that a range-finder can achieve and so the maximum possible value of the range image (in meter).
-
The windowPosition field defines a position in the main 3D window where the camera image will be displayed. The X and Y values for this position are floating point values between 0.0 and 1.0. They specify the position of the center of the camera image, relatively to the top left corner of the main 3D view. This position will scale whenever the main window is resized. Also, the user can drag and drop this camera image in the main Webots window using the mouse. This will affect the X and Y position values.
-
The pixelSize field defines the zoom factor for camera images rendered in the main Webots window (see the windowPosition description). Setting a pixelSize value higher than 1 is useful to better see each individual pixel of the camera image. Setting it to 0 simply turns off the display of the camera image, thus saving computation time.
-
The antiAliasing field switches on or off (the default) anti-aliasing effect on the camera images. Anti-aliasing is a technique that assigns pixel colors based on the fraction of the pixel's area that's covered by the primitives being rendered. Anti-aliasing makes graphics more smooth and pleasing to the eye by reducing aliasing artifacts. Aliasing artifacts can appear as jagged edges (or moiré patterns, strobing, etc.). Anti-aliasing will not be applied if it is not supported by the hardware.
-
If the colorNoise field is greater than 0.0, this adds a gaussian noise to each RGB channel of a color image. This field is useless in case of range-finder cameras. A value of 0.0 corresponds to remove the noise and thus saving computation time. A value of 1.0 corresponds to a gaussian noise having a standard derivation of 255 in the channel representation. More information on noise in the corresponding subsection below.
-
If the rangeNoise field is greater than 0.0, this adds a gaussian noise to each depth value of a range-finder image. This field is useless in case of color cameras. A value of 0.0 corresponds to remove the noise and thus saving computation time. A value of 1.0 corresponds to a gaussian noise having a standard derivation of maxRange meters. More information on noise in the corresponding subsection below.
-
The zoom field may contain a CameraZoom node to provide the camera device with a controllable zoom system. If this field is set to NULL, then no zoom is available on the camera device.
3.5.3 Camera Type
The camera type can be setup by the type field described above.
Color
The color camera allows to get color information from the OpenGL context of the camera. This information can be get by the wb_camera_get_image function, while the red, green and blue channels (RGB) can be extracted from the resulted image by the wb_camera_image_get_*-like functions.
Internally when the camera is refreshed, an OpenGL context is created, and the color or depth information is copied into the buffer which can be get throught the wb_camera_get_image or the wb_camera_get_range_image functions. The format of these buffers are respectively BGRA (32 bits) and float (16 bits). We recommend to use the wb_camera_image_get_*-like functions to access the buffer because the internal format can changed.
Range-Finder
The range-finder camera allows to get depth information (in meters) from the OpenGL context of the camera. This information is obtained through the wb_camera_get_range_image function, while depth information can be extracted from the returned image by using the wb_camera_range_image_get_depth function.
Internally when the camera is refreshed, an OpenGL context is created, and the z-buffer is copied into a buffer of float. As the z-buffer contains scaled and logarithmic values, an algorithm linearizes the buffer to metric values between near and maxRange. This is the buffer which is accessible by the wb_camera_get_range_image function.
Both
This type of camera allows to get both the color data and the range-finder data in the returned buffer using the same OpenGL context. This has been introduced for optimization reasons, mainly for the Microsoft Kinect device, as creating the OpenGL context is costly. The color image and the depth data are obtained by using the wb_camera_get_image and the wb_camera_get_range_image functions as described above.
3.5.4 Frustum
The frustum is the truncated pyramid defining what is visible from the camera. Any 3D shape completely outside this frustum won't be rendered. Hence, shapes located too close to the camera (standing between the camera and the near plane) won't appear. It can be displayed with magenta lines by enabling the View|Optional Rendering|Show Camera Frustums menu item. The near parameter defines the position of the near clipping plane (x, y, -near). The fieldOfView parameter defines the horizontal angle of the frustum. The fieldOfView, the width and the height parameters defines the vertical angle of the frustum according to the formula above.
Generally speaking there is no far clipping plane while this is common in other OpenGL programs. In Webots, a camera can see as far as needed. Nevertheless, a far clipping plane is artificially added in the case of range-finder cameras (i.e. the resulted values are bounded by the maxRange field).
In the case of the spherical cameras, the frustum is quite different and difficult to represent. In comparison with the frustum description above, the near and the far planes are transformed to be sphere parts having their center at the camera position, and the fieldOfView can be greater than Pi.
3.5.5 Noise
It is possible to add quickly a white noise on the cameras by using the colorNoise and the rangeNoise fields (applied respectively on the color cameras and on the range-finder cameras). A value of 0.0 corresponds to an image without noise. For each channel of the image and at each camera refresh, a gaussian noise is computed and added to the channel. This gaussian noise has a standard deviation corresponding to the noise field times the channel range. The channel range is 256 for a color camera and maxRange for a range-finder camera.
3.5.6 Spherical projection
OpenGL is designed to have only planar projections. However spherical projections are very useful for simulating a lidar, a camera pointing on a curved mirror or a biological eye. Therefore we implemented a camera mode rendering spherical projections. It can be enabled simply by switching on the corresponding spherical parameter described above.
Internally, depending on the field of view, a spherical camera is implemented by using between 1 to 6 OpenGL cameras oriented towards the faces of a cube (the activated cameras are displayed by magenta squares when the View|Optional Rendering|Show Camera Frustums menu item is enabled). Moreover an algorithm computing the spherical projection is applied on the result of the subcameras.
So this mode is costly in terms of performance! Reducing the resolution of the cameras and using a fieldOfView which minimizes the number of activated cameras helps a lot to improve the performances if needed.
When the camera is spherical, the image returned by the wb_camera_get_image or the wb_camera_get_range_image functions is a 2-dimensional array (s,t) in spherical coordinates.
Let hFov be the horizontal field of view, and let theta be the angle in radian between the (0, 0, -z) relative coordinate and the relative coordinate of the target position along the xz plane relative to the camera, then s=0 corresponds to a theta angle of -hFov/2, s=(width-1)/2 corresponds to a theta angle of 0, and s=width-1 corresponds to a theta angle of hFov/2.
Similarly, let vFov be the vertical field of view (defined just above), and phi the angle in radian between the (0, 0, -z) relative coordinate and the relative coordinate of the target position along the xy plane relative to the camera, t=0 corresponds to a phi angle of -vFov/2, t=(height-1)/2 corresponds to a phi angle of 0, and t=height-1 corresponds to a phi angle of vFov/2).
3.5.7 Camera Functions
NAME
wb_camera_enable, wb_camera_disable, wb_camera_get_sampling_period - enable and disable camera updatesSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>void wb_camera_enable(WbDeviceTag tag, int ms);
void wb_camera_disable(WbDeviceTag tag);
int wb_camera_get_sampling_period(WbDeviceTag tag);
DESCRIPTION
wb_camera_enable() allows the user to enable a camera update each ms milliseconds.
wb_camera_disable() turns the camera off, saving computation time.
The wb_camera_get_sampling_period() function returns the period given into the wb_camera_enable() function, or 0 if the device is disabled.
NAME
wb_camera_get_fov, wb_camera_set_fov - get and set field of view for a cameraSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>double wb_camera_get_fov(WbDeviceTag tag);
void wb_camera_set_fov(WbDeviceTag tag, double fov);
DESCRIPTION
These functions allow the controller to get and set the value for the field of view (fov) of a camera. The original value for this field of view is defined in the Camera node, as fieldOfView. Note that changing the field of view using wb_camera_set_fov() is possible only if the camera device has a CameraZoom node defined in its zoom field. The minimum and maximum values for the field of view are defined in this CameraZoom node.
NAME
wb_camera_get_width, wb_camera_get_height - get the size of the camera imageSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>int wb_camera_get_width(WbDeviceTag tag);
int wb_camera_get_height(WbDeviceTag tag);
DESCRIPTION
These functions return the width and height of a camera image as defined in the corresponding Camera node.
NAME
wb_camera_get_near - get the near parameter of the camera deviceSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>double wb_camera_get_near(WbDeviceTag tag);
DESCRIPTION
This function returns the near parameter of a camera device as defined in the corresponding Camera node.
NAME
wb_camera_get_type - get the type of the cameraSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>int wb_camera_get_type();
DESCRIPTION
This function returns the type of the camera as defined by the type field of the corresponding Camera node. The constants defined in camera.h are summarized in table 3.1:
| Camera.type | return value |
| "color" | WB_CAMERA_COLOR |
| "range-finder" | WB_CAMERA_RANGE_FINDER |
| both" | WB_CAMERA_BOTH |
Table 3.1: Return values for the wb_camera_get_type() function
|
|
NAME
wb_camera_get_image, wb_camera_image_get_red, wb_camera_image_get_green, wb_camera_image_get_blue, wb_camera_image_get_grey - get the image data from a cameraSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>const unsigned char *wb_camera_get_image(WbDeviceTag tag);
unsigned char wb_camera_image_get_red(const unsigned char *image, int width, int x, int y);
unsigned char wb_camera_image_get_green(const unsigned char *image, int width, int x, int y);
unsigned char wb_camera_image_get_blue(const unsigned char *image, int width, int x, int y);
unsigned char wb_camera_image_get_grey(const unsigned char *image, int width, int x, int y);
DESCRIPTION
The wb_camera_get_image() function reads the last image grabbed by the camera. The image is coded as a sequence of three bytes representing the red, green and blue levels of a pixel. Pixels are stored in horizontal lines ranging from the top left hand side of the image down to bottom right hand side. The memory chunk returned by this function must not be freed, as it is handled by the camera itself. The size in bytes of this memory chunk can be computed as follows:
byte_size = camera_width * camera_height * 4
Internal pixel format of the buffer is BGRA (32 bits). Attempting to read outside the bounds of this chunk will cause an error.
The wb_camera_image_get_red(), wb_camera_image_get_green() and wb_camera_image_get_blue() macros can be used for directly accessing the pixel RGB levels from the pixel coordinates. The wb_camera_image_get_grey() macro works in a similar way but returns the grey level of the specified pixel by averaging the three RGB components. In the C version, these four macros return an unsigned char in the range [0..255]. Here is a C usage example:
|
|
|
|
|
|
|
|
NAME
wb_camera_get_range_image, wb_camera_range_image_get_depth, wb_camera_get_max_range - get the range image and range data from a range-finder cameraSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>const float *wb_camera_get_range_image(WbDeviceTag tag);
float wb_camera_range_image_get_depth(const float *range_image, int width, int x, int y);
double wb_camera_get_max_range(WbDeviceTag tag);
DESCRIPTION
The wb_camera_get_range_image() macro allows the user to read the contents of the last range image grabbed by a range-finder camera. The range image is computed using the depth buffer produced by the OpenGL rendering. Each pixel corresponds to the distance expressed in meter from the object to the plane defined by the equation z = 0 within the coordinates system of the camera. The bounds of the range image is determined by the near clipping plane (defined by the near field) and the far clipping plane (see the maxRange field). The range image is coded as an array of single precision floating point values corresponding to the range value of each pixel of the image. The precision of the range-finder values decreases when the objects are located farther from the near clipping plane. Pixels are stored in scan lines running from left to right and from top to bottom. The memory chunk returned by this function shall not be freed, as it is managed by the camera internally. The size in bytes of the range image can be computed as follows:
size = camera_width * camera_height * sizeof(float)
Attempting to read outside the bounds of this memory chunk will cause an error.
The wb_camera_range_image_get_depth() macro is a convenient way to access a range value, directly from its pixel coordinates. The camera_width parameter can be obtained from the wb_camera_get_width() function. The x and y parameters are the coordinates of the pixel in the image.
The wb_camera_get_max_range() function returns the value of the maxRange field.
|
|
NAME
wb_camera_save_image - save a camera image in either PNG or JPEG formatSYNOPSIS [C++] [Java] [Python] [Matlab]
#include <webots/camera.h>int wb_camera_save_image(WbDeviceTag tag, const char *filename, int quality);
DESCRIPTION
The wb_camera_save_image() function allows the user to save a tag image which was previously obtained with the wb_camera_get_image() function. The image is saved in a file in either PNG or JPEG format. The image format is specified by the filename parameter. If filename is terminated by .png, the image format is PNG. If filename is terminated by .jpg or .jpeg, the image format is JPEG. Other image formats are not supported. The quality parameter is useful only for JPEG images. It defines the JPEG quality of the saved image. The quality parameter should be in the range 1 (worst quality) to 100 (best quality). Low quality JPEG files will use less disk space. For PNG images, the quality parameter is ignored.
The return value of the wb_camera_save_image() is 0 in case of success. It is -1 in case of failure (unable to open the specified file or unrecognized image file extension).