Webots Reference Manual

previous page go up next page

Thanks

1. Introduction

2. Node Chart

3. Nodes and API Functions

4. Motion Functions

5. Prototypes

6. Physics Plugin

7. Fast2D Plugin

8. MTN Functions

9. Webots World Files

     

3.5 Camera

Derived from Solid.

Camera {
  SFFloat    fieldOfView      0.7854
  SFInt32    width            64
  SFInt32    height           64
  SFString   type             "color"
  SFBool     display          TRUE
  SFFloat    near             0.01
  SFFloat    far              50.0
  SFVec2f    windowPosition   0 0
  SFInt32    pixelSize        1
  SFBool     antiAliasing     FALSE
  SFInt32    gaussianNoise    0.0
}

3.5.1 Description

The Camera node is used to model a robot's on-board camera or range-finder. The camera can be either a color camera, a black and white camera, or a range-finder device, as defined in the type field of the node. It can model a linear camera (if the height field is set to 1). The range-finder device relies on the OpenGL depth buffer information.

3.5.2 Field Summary

  • fieldOfView: horizontal field of view angle of the camera. The value ranges from 0 to pi 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", "black and white" or "range-finder"

  • display: specify if a camera window should pop up, displaying the image taken by the camera. If such a camera window is used, it should not be iconified or covered by any other window, otherwise the image data might be corrupted. It is often useful to set this field to TRUE for debugging a controller program. However, it is safer to set it to FALSE for more extensive experiments.

  • The near and far field define the distance from the camera to the near and far OpenGL clipping planes. These planes are parallel to the camera retina (i.e., projection plane). Along with the fieldOfView field, they define the viewing frustum of the camera. Any 3D shape outside this frustum won't be rendered. Hence, shapes too far away (below the far plane) won't appear in the camera view. Similarly, shapes too close (standing before the near plane) won't appear either.

  • The windowPosition field defines a position in the main Webots window where the camera image will be displayed. The X and Y values for this position are floating point values between 0 and 1 inclusive. 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. If one of these values is set to -1, it means that the camera image won't appear in the main window of Webots, but in a small camera window instead.

  • 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.

  • 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.).

  • If the gaussianNoise field is greater than 0, this adds gaussian noise to the camera images. The gaussianNoise field accepts values between 0 and 255. When gaussian noise is added, the simulated camera images do more accurately match real camera images; RGB values of nearby pixel become less homogenous.

Note: Webots provides two distinct implementation of the Camera devices. The first implementation (used by default) displays the camera images in small windows, outside of Webots' main window. The second implementation renders the images directly inside Webots' main window, in thin mouse-draggable magenta frames. An important difference is that cameras of the second type provide images that more faithfully match the rendering content of the main window, while cameras of the first type will leave out the scene's shadows and all the Pen devices drawings on the floor. If you would like cameras that display shadows and pen drawings, you should use the second type of camera. To switch to the second type of cameras, change the windowPosition field as indicated above.

3.5.3 Camera Functions

NAME

   wb_camera_enable, wb_camera_disable - enable and disable camera updates

C SYNOPSIS

  #include <webots/camera.h>

  void wb_camera_enable(WbDeviceTag camera, int ms);
  void wb_camera_disable(WbDeviceTag camera);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  void Camera::enable(int ms);
  void Camera::disable();

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  void Camera.enable(int ms);
  void Camera.disable();

PYTHON SYNOPSIS

  from controller import Camera

  none Camera.enable(int ms)
  none Camera.disable()

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.

NAME

   wb_camera_get_fov, wb_camera_set_fov - get and set field of view for a camera

C SYNOPSIS

  #include <webots/camera.h>

  double wb_camera_get_fov(WbDeviceTag camera);
  void wb_camera_set_fov(WbDeviceTag camera, double fov);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  double Camera::getFov();
  void Camera::setFov(double fov);

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  double Camera.getFov();
  void Camera.setFov(double fov);

PYTHON SYNOPSIS

  from controller import Camera

  float Camera.getFov()
  none Camera::setFov(float 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 however, that changing the field of view using wb_camera_set_fov() will not change the value of the fieldOfView field on the simulator side. It will only affect the controller side, making new rendered images use the specified field of view for the specified camera.

NAME

   wb_camera_get_width, wb_camera_get_height - get the size of the camera image

C SYNOPSIS

  #include <webots/camera.h>

  int wb_camera_get_width(WbDeviceTag camera);
  int wb_camera_get_height(WbDeviceTag camera);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  int Camera::getWidth();
  int Camera::getHeight();

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  int Camera.getWidth();
  int Camera.getHeight();

PYTHON SYNOPSIS

  from controller import Camera

  int Camera.getWidth()
  int Camera.getHeight()

DESCRIPTION

These functions return the width and height of a camera image as defined in the corresponding Camera node.

NAME

   wb_camera_get_near, wb_camera_get_far - get the near and far parameters of the camera device

C SYNOPSIS

  #include <webots/camera.h>

  double wb_camera_get_near(WbDeviceTag camera);
  double wb_camera_get_far(WbDeviceTag camera);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  double Camera::getNear();
  double Camera::getFar();

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  double Camera.getNear();
  double Camera.getFar();

PYTHON SYNOPSIS

  from controller import Camera

  float Camera.getNear()
  float Camera.getFar()

DESCRIPTION

These functions return the near and far parameters of a camera device as defined in the corresponding Camera node.

NAME

   wb_camera_get_type - get the type of the camera

C SYNOPSIS

  #include <webots/camera.h>

  int wb_camera_get_type();

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  int Camera::getCameraType();

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  int Camera.getCameraType();

PYTHON SYNOPSIS

  from controller import Camera

  int Camera.getCameraType()

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
"black and white"WB_CAMERA_BLACK_AND_WHITE
"range-finder"WB_CAMERA_RANGE_FINDER

Table 3.1: Return values for the wb_camera_get_type() function

Note: In the oriented-object APIs, the WB_CAMERA_* constants are available as static integers of the Camera class (for example, Camera::COLOR).

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 camera

C SYNOPSIS

  #include <webots/camera.h>

  unsigned char *wb_camera_get_image(WbDeviceTag camera);
  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);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  unsigned char *Camera::getImage();
  static unsigned char Camera::imageGetRed(const unsigned char *image, int width, int x, int y);
  static unsigned char Camera::imageGetGreen(const unsigned char *image, int width, int x, int y);
  static unsigned char Camera::imageGetBlue(const unsigned char *image, int width, int x, int y);
  static unsigned char Camera::imageGetGrey(const unsigned char *image, int width, int x, int y);

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  int[] Camera.getImage();
  static int Camera.imageGetRed(int[] image, int width, int x, int y);
  static int Camera.imageGetGreen(int[] image, int width, int x, int y);
  static int Camera.imageGetBlue(int[] image, int width, int x, int y);
  static int Camera.imageGetGrey(int[] image, int width, int x, int y);
  static int Camera.pixelGetRed(int pixel);
  static int Camera.pixelGetGreen(int pixel);
  static int Camera.pixelGetBlue(int pixel);
  static int Camera.pixelGetGrey(int pixel);

PYTHON SYNOPSIS

  from comtroller import Camera

  string Camera.getImage()
  list<list<list<int>>> Camera.getImageArray()
  static int Camera.imageGetRed(string image, int width, int x, int y)
  static int Camera.imageGetGreen(string image, int width, int x, int y)
  static int Camera.imageGetBlue(string image, int width, int x, int y)
  static int Camera.imageGetGrey(string 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 * 3

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:


  ...
  const unsigned char *image = wb_camera_get_image(camera);
  for (int x = 0; x < image_width; x++)
    for (int y = 0; y < image_height; y++) {
      int r = wb_camera_image_get_red(image, image_width, x, y);
      int g = wb_camera_image_get_green(image, image_width, x, y);
      int b = wb_camera_image_get_blue(image, image_width, x, y);
      printf("red=%d, green=%d, blue=%d", r, g, b);
    }
  ...

Note: The Java version of Camera.getImage() returns an array of int (int[]). The length of this array corresponds to the number of pixels in the image, that is the width multiplied by the height of the image. Each int element of the array represents one pixel coded in RGB with 8 bits of red, 8 bits of green and 8 bits of blue. For example red is 0xff0000, green is 0x00ff00, etc. The Camera.pixelGetRed(), Camera.pixelGetGreen() and Camera.pixelGetBlue() Java functions can be used to decode a pixel value for the red, green and blue components. The Camera.pixelGetGrey() function works in a similar way, but returns the grey level of the pixel by averaging the three RGB components. Each of these four functions take an int pixel argument and return an int color/grey component in the range [0..255]. Here is a Java usage example:


  ...
  int[] image = camera.getImage();
  for (int i=0; i < image.length; i++) {
    int pixel = image[i];
    int r = Camera.pixelGetRed(pixel);
    int g = Camera.pixelGetGreen(pixel);
    int b = Camera.pixelGetBlue(pixel);
    System.out.println("red=" + r + " green=" + g + " blue=" + b);
  }
  ...

Note: The getImage() of Python returns a string. This string is closely related with the const char * of the C API. It can be used directly in the constructor of the PIL Image class (for Windows users; PIL is not a member of the standard Python installation. But it can be downloaded separately). Here is an example:


  import Image
  ...
  cameraData=camera.getImage()
  image=Image.fromstring(
                'RGB',
                (camera.getWidth(), camera.getHeight()),
                cameraData)
  ...
      

Another way to use the camera in Python is to get the image by getArrayImage() which returns a list<list<list<int>>>. This three dimensional list can be directly used for accessing to the pixels. Here is an example:


  ...
  image = camera.getArrayImage()
  for x in range(0,width)
    for y in range(0,height)
      red   = image[x][y][0];
      green = image[x][y][1];
      blue  = image[x][y][2];
      print "r="+str(red)+" g="+str(green)+" b="+str(blue)
  ...
      

NAME

   wb_camera_get_range_image, wb_camera_range_image_get_value - get the range image and range data from a range-finder camera

C SYNOPSIS

  #include <webots/camera.h>

  float *wb_camera_get_range_image(WbDeviceTag camera);
  float wb_camera_range_image_get_value(const float *range_image, float camera_near, float camera_far, int width, int x, int y);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  float *Camera::getRangeImage();
  static float Camera::rangeImageGetValue(const float *rangeImage, float cameraNear, float cameraFar, int width, int x, int y);

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  float[] Camera.getRangeImage();
  static float Camera::rangeImageGetValue(float[] rangeImage, float cameraNear, float cameraFar, int width, int x, int y);

PYTHON SYNOPSIS

  from controller import Camera

  list<float> Camera.getRangeImage()
  list<list<float>> Camera.getRangeImageArray()
  static float Camera.rangeImageGetValue(list<float> rangeImage, float cameraNear, float cameraFar, int width, int x, int y)

DESCRIPTION

The wb_camera_get_range_image() macro allows you to read the contents of the last range image grabbed by a range-finder camera. The range image corresponds to the depth buffer produced by the OpenGL rendering. For each pixel, it provides the distance from the object to the camera. However, it is necessary to use the wb_camera_range_image_get_value() macro to obtain linear distance information expressed in meters. Otherwise, the raw value in the buffer is non-linear, corresponding to the raw OpenGL depth buffer. 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. Pixels are stored in lines ranging from the bottom left hand side of the image up to top right hand side. The memory chunk returned by this function doesn't need to be freed, as it is handled by the camera itself. The size in bytes of this memory chunk can be computed as follow:

size = camera_width * camera_height * sizeof(float)

Attempting to read outside the bounds of this chunk will cause an error.

The wb_camera_range_image_get_value() macro is a useful helper for directly accessing the pixel range value from the pixel coordinates. This macro transforms the distance value, so that it is linear and expressed in meters. The camera_near, camera_far and camera_width parameters can be obtained from the wb_camera_get_near(), wb_camera_get_far() and wb_camera_get_width() functions respectively. The x and y are the coordinates of the pixel in the image.

Note: The Python Camera class has two methods fore getting the camera image. The getRangeImage() returns an unidimensional list of floats, while the getRangeImageArray() returns a bidimentional list of floats. Their content are identical but their handling is of course different.

NAME

   wb_camera_move_window - move the camera window

C SYNOPSIS

  #include <webots/camera.h>

  void wb_camera_move_window(WbDeviceTag camera, int x, int y);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  void Camera::moveWindow(int x, int y);

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  void Camera.moveWindow(int x, int y);

PYTHON SYNOPSIS

  from controller import Camera

  none Camera.moveWindow(int x, int y)

DESCRIPTION

The wb_camera_move_window() function allows you to move the window containing the camera image on the computer desktop to the x and y coordinates.

NAME

   wb_camera_save_image - save a camera image in either PNG or JPEG format

C SYNOPSIS

  #include <webots/camera.h>

  int wb_camera_save_image(WbDeviceTag camera, const char *filename, int quality);

C++ SYNOPSIS

  #include <webots/Camera.hpp>

  int Camera::saveImage(const std::string &filename, int quality);

JAVA SYNOPSIS

  import com.cyberbotics.webots.controller.Camera;

  int Camera.saveImage(String filename, int quality);

PYTHON SYNOPSIS

  from controller import Camera

  int Camera.saveImage(string filename, int quality)

DESCRIPTION

The wb_camera_save_image() function allows you to save a camera 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).

previous page go up next page
^ page top ^

  E-mail to webmaster Last updated: Copyright © 2008 Cyberbotics Ltd.