ALVideoDevice API

NAOqi Vision - Overview | API | Tutorial | ALVideoDevice - Advanced


Namespace : AL

#include <alproxies/alvideodeviceproxy.h>

Method list

As any module, this module inherits methods from ALModule API. It also has the following specific methods:

class ALVideoDeviceProxy

Module Subscription Management

void ALVideoDeviceProxy::unsubscribe(const std::string& Name)

Unregisters a module from ALVideoDevice.

Parameters:
  • Name – Name under which the module is known from the video system.

alvideodevice_subscribe.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_subscribe pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Subscribe a Vision Module to ALVideoDevice, starting the
  // frame grabber if it was not started before.
  std::string subscriberID = "subscriberID";
  int fps = 5;
  // The subscriberID can be altered if other instances are already running
  subscriberID = cameraProxy.subscribe(subscriberID, AL::kVGA, AL::kRGBColorSpace, fps);

  // Do something...

  // Unsubscribe the V.M.
  cameraProxy.unsubscribe(subscriberID);

  return 0;
}
void ALVideoDeviceProxy::onClientDisconnected(const std::string& eventName, const AL::ALValue& eventContents, const std::string& message)

Callback when client is disconnected

Parameters:
  • eventName – The echoed event name
  • eventContents – The name of the client that has disconnected
  • message – Message provided when subscribing.

Camera Management

int ALVideoDeviceProxy::getCameraModel(const int& CameraIndex)

Gets the camera model of the default active camera.

Parameters:
  • CameraIndex – Index of the camera in the video system.
Returns:

cameramodel.

bool ALVideoDeviceProxy::startFrameGrabber(const int& CameraIndex)

Opens and initialize the video source device if it was not already opened.

Note

The first module subscribing to ALVideoDevice will launch it automatically, so the main purpose of this method is to reduce time when the first vision module is subscribing.

Parameters:
  • CameraIndex – Index of the camera in the video system.
Returns:

true if success.

bool ALVideoDeviceProxy::stopFrameGrabber(const int& CameraIndex)

Closes the video source device.

Note

When the last vision module subscribed to ALVideoDevice unsubscribes, this doesn’t close the video source device as we assume that if some video was requested before, video will be again requested latter. But if this is not the case, closing the video source will save processing resources.

Parameters:
  • CameraIndex – Index of the camera in the video system.
Returns:

true if success.

bool ALVideoDeviceProxy::isFrameGrabberOff(const int& CameraIndex)

Asks if the framegrabber is running or not.

Parameters:
  • CameraIndex – Index of the camera in the video system.
Returns:

true if success.

int ALVideoDeviceProxy::getFrameRate(const int& CameraIndex)

Gets the internal frame rate of the video source.

Parameters:
  • CameraIndex – Index of the camera in the video system.
Returns:

video source framerate. -1: can’t access video source.

int ALVideoDeviceProxy::getResolution(const int& CameraIndex)

Gets the resolution of the video source before eventual conversion.

Parameters:
  • CameraIndex – Index of the camera in the video system.
Returns:

resolution or -1: can’t access video source.

int ALVideoDeviceProxy::getColorSpace(const int& CameraIndex)

Get the color space of the video source before enventual conversion.

Parameters:
  • CameraIndex – Index of the camera in the video system.
Returns:

colorspace or -1: can’t access video source.

Mono Stream Management

std::string ALVideoDeviceProxy::subscribeCamera(const std::string& Name, const int& CameraIndex, const int& Resolution, const int& ColorSpace, const int& Fps)

Subscribes to ALVideoDevice. When a Video Module registers to ALVideoDevice, a buffer of the requested image format is added to the buffers list. Returns the name under which the module will be known from ALVideoDevice (useful when several modules try to subscribe using the same name, the 3rd one getting _3 added to its name for instance).

Parameters:
  • Name – Name of the subscribing module.
  • CameraIndex – Index of the camera in the video system.
  • Resolution – Resolution requested (see resolution).
  • ColorSpace – Colorspace requested (see colorspace).
  • Fps – Fps (frames per second) requested to the video source (see framerate).
Returns:

Name under which the module is known from ALVideoDevice, NULL if failed.

Note

Compared to a local module, the obtained framerate for a remote module will depend on the network available bandwith (e.g. we can reach raw 1280x960@10fps using a Gigabit Ethernet connection with the HD camera).

int ALVideoDeviceProxy::getFrameRate(const std::string& Name)

Gets the frame rate that a particular Vision Module has requested to the camera. This doesn’t mean the video source is able to run at this frame rate (see ALVideoDeviceProxy::getFrameRate() to know the video source framerate). This doesn’t either mean that a remote module will obtain images at this framerate due to network bandwith limitations.

Parameters:
  • Name – Name of the subscribing module.
Returns:

module framerate or -1: can’t access video source.

bool ALVideoDeviceProxy::setFrameRate(const std::string& Name, const int& Fps)

Changes the framerate requested to the video source by the subscribed module.

Parameters:
  • Name – Name of the subscribing module.
  • Fps – Fps (frames per second) requested to the video source (see framerate).

Note

The requested framerate will be achieved locally. Remotely, the achieved framerate will depend on the network available bandwith (e.g. we can reach raw 1280x960@10fps using a Gigabit Ethernet connection with the HD camera).

Returns:true if success.
int ALVideoDeviceProxy::getActiveCamera(const std::string& Name)

Gets the current active camera for the specified module.

Parameters:
  • Name

    Name of the subscribing module.

    return:cameraindex or -1: can’t access video source.
bool ALVideoDeviceProxy::setActiveCamera(const std::string& Name, const int& ActiveCamera)

Sets the current active camera for the specified module.

Parameters:
  • Name – Name of the subscribing module.
  • ActiveCamera – Camera index (see cameraindex).
Returns:

true if success.

int ALVideoDeviceProxy::getResolution(const std::string& Name)

Gets the current resolution requested for the specified module.

Parameters:
  • Name – Name of the subscribing module.
Returns:

resolution.

bool ALVideoDeviceProxy::setResolution(const std::string& Name, const int& Resolution)

Sets the size of the output image for the specified module.

Parameters:
  • Name – Name of the subscribing module.
  • Resolution – Resolution requested (see resolution).
Returns:

true if success.

int ALVideoDeviceProxy::getColorSpace(const std::string& Name)

Gets the current color space requested for the specified module.

Parameters:
  • Name – Name of the subscribing module.
Returns:

colorspace or -1: can’t access video source.

bool ALVideoDeviceProxy::setColorSpace(const std::string& Name, const int& ColorSpace)

Sets the current color space requested for the specified module.

Parameters:
  • Name – Name of the subscribing module.
  • ColorSpace – Colorspace requested (see colorspace).
Returns:

true if success.

int ALVideoDeviceProxy::getCameraParameter(const std::string& Name, const int& Id)

Gets a camera’s parameter from the module current active camera. This method will probe for value of the current active camera of the module.

Parameters:
Returns:

Parameter’s value.

bool ALVideoDeviceProxy::setCameraParameter(const std::string& Name, const int& Id, const int& NewValue)

Sets the value of a specific parameter for the module current active camera.

Parameters:
  • Name – Name of the subscribing module.
  • Id – Id of the camera parameter (see Modifying camera parameters).
  • NewValue – New value to set.
Returns:

true if success.

bool ALVideoDeviceProxy::setCameraParameterToDefault(const std::string& Name, const int& Id)

Sets a camera’s parameter to its default value.

Parameters:
Returns:

true if success.

AL::ALImage* ALVideoDeviceProxy::getDirectRawImageLocal(const std::string& Name)

Retrieves the latest image from the video source and returns a pointer to the locked AL::ALImage, with data array pointing directly to raw data. There is no format conversion and no copy of the raw buffer.

Warning

  • Direct raw images are encoded using the same layout than the one used with AL::kYUV422ColorSpace.
  • When image is not necessary anymore, a call to releaseDirectRawImage() is requested.
  • When using this mode for several modules, if they need raw data for more than 25ms check that you have strictly less modules in this requesting direct raw images than the amount of kernel buffers.
  • Release all kernel buffers (using releaseDirectRawImage) before doing any action requesting a modification of the video source mode (e.g. resolution, switch between cameras).
  • Image pointer is valid only for local modules. For remote modules, the address space is different from the one of NAOqi.
Parameters:
  • Name – Name of the subscribing module.
Returns:

Pointer to the locked AL::ALImage buffer, NULL if error.

AL::ALValue ALVideoDeviceProxy::getDirectRawImageRemote(const std::string& Name)

Retrieves the latest image from the video source and send the data coming directly from the raw buffer as an ALValue through the network (no format conversion).

Warning

  • Direct raw images are encoded using the same layout than the one used with AL::kYUV422ColorSpace.
Parameters:
  • Name – Name of the subscribing module.
Returns:

Container of image.

bool ALVideoDeviceProxy::releaseDirectRawImage(const std::string& Name)

Release image buffer locked by getDirectRawImageLocal(). If the module has no locked image buffer, does nothing.

Parameters:
  • Name – Name of the subscribing module.
Returns:

true if success

AL::ALImage* ALVideoDeviceProxy::getImageLocal(const std::string& Name)

Retrieves the latest image from the video source, applies eventual transformations to the image to provide the format requested by the vision module and returns a pointer to a locked AL::ALImage.

Warning

  • When the image is not necessary anymore, a call to releaseImage() is requested. If the module didn’t release the previous image, returns NULL.
  • Image pointer is valid only if your module is running locally, not for remote modules.
Parameters:
  • Name – Name of the subscribing module.
Returns:

Pointer to the locked image buffer, NULL if error (e.g. if the previous image was not released).

alvideodevice_imagelocal.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_imageremote pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Subscribe a Vision Module to ALVideoDevice, starting the
  // frame grabber if it was not started before.
  std::string subscriberID = "subscriberID";
  int fps = 5;
  // The subscriberID can be altered if other instances are already running
  subscriberID = cameraProxy.subscribe(subscriberID, AL::kVGA, AL::kRGBColorSpace, fps);

  // Retrieve the current image.
  const ALImage* image = cameraProxy.getImageLocal(subscriberID);
  if (image == NULL) {
    std::cerr << "Could not retrieve current image." << std::endl;
    return 0;
  }
  else {
    std::cout << "Image retrieved." << std::endl;
  }

  cameraProxy.releaseImage(subscriberID);

  // Unsubscribe the V.M.
  cameraProxy.unsubscribe(subscriberID);

  return 1;
}
AL::ALValue ALVideoDeviceProxy::getImageRemote(const std::string& Name)

Retrieves the latest image from the video source, applies eventual transformations to the image to provide the format requested by the vision module and send it as an ALValue through the network.

Parameters:
  • Name – Name of the subscribing module.
Returns:

Container of image.

alvideodevice_imageremote.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_imageremote pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Subscribe a Vision Module to ALVideoDevice, starting the
  // frame grabber if it was not started before.
  std::string subscriberID = "subscriberID";
  int fps = 5;
  // The subscriberID can be altered if other instances are already running
  subscriberID = cameraProxy.subscribe(subscriberID, AL::kVGA, AL::kRGBColorSpace, fps);

  // Retrieve the current image.
  AL::ALValue results;
  results = cameraProxy.getImageRemote(subscriberID);
  const unsigned char* imageData =  static_cast<const unsigned char*>(results[6].GetBinary());

  if (imageData == NULL) {
    std::cerr << "Could not retrieve current image." << std::endl;
    return 0;
  }
  else {
    std::cout << "Image retrieved." << std::endl;
  }

  cameraProxy.releaseImage(subscriberID);

  // Unsubscribe the V.M.
  cameraProxy.unsubscribe(subscriberID);

  return 1;
}
bool ALVideoDeviceProxy::releaseImage(const std::string& Name)

Release image buffer locked by getImageLocal(). If module had no locked image buffer, does nothing.

Parameters:
  • Name – Name of the subscribing module.
Returns:

true if success

Note

It is not mandatory to use releaseImage to release an image obtained by getImageRemote. However, it’s a good habit to place it in order to ease the switch from a remote behavior to a local one and this will not use CPU (this method returns directly when it follows a getImageRemote).

alvideodevice_imagelocal.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_imageremote pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Subscribe a Vision Module to ALVideoDevice, starting the
  // frame grabber if it was not started before.
  std::string subscriberID = "subscriberID";
  int fps = 5;
  // The subscriberID can be altered if other instances are already running
  subscriberID = cameraProxy.subscribe(subscriberID, AL::kVGA, AL::kRGBColorSpace, fps);

  // Retrieve the current image.
  const ALImage* image = cameraProxy.getImageLocal(subscriberID);
  if (image == NULL) {
    std::cerr << "Could not retrieve current image." << std::endl;
    return 0;
  }
  else {
    std::cout << "Image retrieved." << std::endl;
  }

  cameraProxy.releaseImage(subscriberID);

  // Unsubscribe the V.M.
  cameraProxy.unsubscribe(subscriberID);

  return 1;
}

Multi Stream Management

std::string ALVideoDeviceProxy::subscribeCameras(const std::string& Name, const AL::ALValue& CameraIndexes, const AL::ALValue& Resolutions, const AL::ALValue& ColorSpaces, const int& Fps)

Subscribes to Video Inpute System. When a Video Module subscribes to the video input system, a buffer of the requested image resolution is added to the buffers list.

Parameters:
  • Name – Name of the subscribing module.
  • CameraIndexes – Array of the requested camera indexes. You can’t have the same camera index several time.
  • Resolutions – Array of the resolutions requested (see resolution).
  • ColorSpaces – Array of the color spaces requested (see colorspace.
  • Fps – Fps (frames per second) requested to the video source (see framerate).
Returns:

Name under which the module is known from the video system.

Note

  • By default the active camera will be the first camera in the array.
  • Returned registered name could be different to the subscribing module name.
AL::ALValue ALVideoDeviceProxy::getActiveCameras(const std::string& Name)

Gets current active cameras for the specified module.

Parameters:
  • Name

    Name of the subscribing module.

    return:Array of camera indexes (see cameraindex) or -1: can’t access video source.
AL::ALValue ALVideoDeviceProxy::setActiveCameras(const std::string& Name, const AL::ALValue& ActiveCameras)

Sets the current active cameras for the specified module.

Parameters:
  • Name – Name of the subscribing module.
  • ActiveCameras – Array of the requested camera indexes (see cameraindex).
Returns:

Array of booleans with true if success.

AL::ALValue ALVideoDeviceProxy::getResolutions(const std::string& Name)

Gets the current resolutions requested for the specified module.

Parameters:
  • Name – Name of the subscribing module.
Returns:

Array of resolutions (see resolution).

AL::ALValue ALVideoDeviceProxy::setResolutions(const std::string& Name, const AL::ALValue& Resolutions)

Sets the size of the output image for the specified module.

Parameters:
  • Name – Name of the subscribing module.
  • Resolution – Array of resolutions requested (see resolution).
Returns:

Array of booleans with true if success.

AL::ALValue ALVideoDeviceProxy::getColorSpaces(const std::string& Name)

Gets the current color spaces requested for the specified module.

Parameters:
  • Name – Name of the subscribing module.
Returns:

Array of color spaces (see colorspace).

AL::ALValue ALVideoDeviceProxy::setColorSpaces(const std::string& Name, const AL::ALValue& ColorSpaces)

Sets the current color spaces requested for the specified module.

Parameters:
  • Name – Name of the subscribing module.
  • ColorSpaces – Array of color spaces requested (see colorspace).
Returns:

Array of booleans with true if success

AL::ALValue ALVideoDeviceProxy::getCamerasParameter(const std::string& Name, const int& Id)

Gets a camera’s parameter from the module current active cameras. This method will probe for value of the current active camera of the module.

Parameters:
Returns:

Parameter’s values.

AL::ALValue ALVideoDeviceProxy::setCamerasParameter(const std::string& Name, const int& Id, const AL::ALValue& NewValue)

Sets the values of a specific parameter for the module current active cameras.

Parameters:
  • Name – Name of the subscribing module.
  • Id – Id of the camera parameter (see Modifying camera parameters).
  • NewValue – New value to set.
Returns:

Array of booleans with true if success.

AL::ALValue ALVideoDeviceProxy::setCamerasParameterToDefault(const std::string& Name, const int& Id)

Sets a camera’s parameter to its default value.

Parameters:
Returns:

Array of booleans with true if success.

AL::ALValue ALVideoDeviceProxy::getDirectRawImagesLocal(const std::string& Name)

Retrieves the latest images from the video source and returns pointers to the locked AL::ALImage, with data array pointing directly to raw data. There is no format conversion and no copy of the raw buffer.

Warning

  • When images are not necessary anymore, a call to releaseDirectRawImages() is requested.
  • When using this mode for several modules, if they need raw data for more than 25ms check that you have strictly less modules in this requesting direct raw images than the amount of kernel buffers.
  • Release all kernel buffers (using releaseDirectRawImages) before doing any action requesting a modification of the video source mode (e.g. resolution, switch between cameras).
  • Image pointers are valid only for local modules. For remote modules, the address space is different from the one of NAOqi.
Parameters:
  • Name – Name of the subscribing module.
Returns:

Array of pointers to the locked AL::ALImage buffer, NULL if error.

AL::ALValue ALVideoDeviceProxy::getDirectRawImagesRemote(const std::string& Name)

Retrieves the latest images from the video source and send the data coming directly from the raw buffer as an ALValue through the network (no format conversion).

Parameters:
  • Name – Name of the subscribing module.
Returns:

Container of images.

AL::ALValue ALVideoDeviceProxy::releaseDirectRawImages(const std::string& Name)

Release image buffer locked by getDirectRawImagesLocal(). If the module has no locked image buffer, does nothing.

Parameters:
  • Name – Name of the subscribing module.
Returns:

true if success

AL::ALValue ALVideoDeviceProxy::getImagesLocal(const std::string& Name)

Retrieves the latest images from the video source, applies eventual transformations to the images to provide the format requested by the vision module and returns pointers to locked AL::ALImage.

Warning

  • When the images are not necessary anymore, a call to releaseImages() is requested. If the module didn’t release the previous image, returns NULL.
  • Image pointers are valid only if your module is running locally, not for remote modules.
Parameters:
  • Name – Name of the subscribing module.
Returns:

Array of pointers to locked AL::ALImage buffers, NULL if error (e.g. if the previous images was not released).

AL::ALValue ALVideoDeviceProxy::getImagesRemote(const std::string& Name)

Retrieves the latest images from the video source, applies eventual transformations to the images to provide the format requested by the vision module and send it as an ALValue through the network.

Parameters:
  • Name – Name of the subscribing module.
Returns:

Container of images.

AL::ALValue ALVideoDeviceProxy::releaseImages(const std::string& Name)

Release image buffers locked by getImagesLocal(). If module had no locked image buffers, does nothing.

Parameters:
  • Name – Name of the subscribing module.
Returns:

Array of booleans with true if success.

Note

It is not mandatory to use releaseImages to release an image obtained by getImagesRemote. However, it’s a good habit to place it in order to ease the switch from a remote behavior to a local one and this will not use CPU (this method returns directly when it follows a getImagesRemote).

Video Recording

bool ALVideoDeviceProxy::recordVideo(const std::string& Name, const std::string& Path, const int& TotalNumber, const int& Period)

Records in background an .arv raw format video from the images processed by the module.

Parameters:
  • Name – Name of the subscribing module.
  • Path – Name with the absolute path (pathToMyFile/filename.arv) of the arv video file to record
  • TotalNumber – number of images to be recorded. 0xFFFFFFFF for “unlimited”
  • Period – one image recorded every pPeriod images
Returns:

true if success.

alvideodevice_subscribe.cpp

import time
#import Image

from naoqi import ALProxy
import vision_definitions


# Put here IP and Port of a broker containg basicMotionDetector
IP = "127.0.0.1"  # Put here the IP address of your robot
PORT=9559

#________________________________
# Get Proxy on ALVideoDevice
#________________________________

try:
  camProxy = ALProxy("ALVideoDevice",IP,PORT)
except Exception,e:
  print "Error when creating vision proxy:"
  print str(e)
  exit(1)

#________________________________
# Vision module creation
#________________________________

resolution = vision_definitions.kQVGA
colorSpace = vision_definitions.kYUV422ColorSpace
fps = 30

nameId = "pythonVM"
nameId = camProxy.subscribe(nameId, resolution, colorSpace, fps)

#________________________________
# Ask to grab a maximum of 3500
# images obtained by the vision module
#________________________________

print  "set recording file"
camProxy.recordVideo(nameId, "/home/nao/myVideo", 3500, 1)

print  "launch recording"

#________________________________
# The vision module requests 300 images
#________________________________

for i in range(0, 300):
  image = camProxy.getImageLocal(nameId)
  camProxy.releaseImage(nameId)
  time.sleep(0.030)

#________________________________
# Stop manually the recording
# after 300 images
#________________________________

print "finishing"
camProxy.stopVideo(nameId)
camProxy.unsubscribeAllInstances(nameId)

print 'end of script'
bool ALVideoDeviceProxy::stopVideo(const std::string& Name)

Stops writing the video sequence.

Parameters:
  • Name – Name of the subscribing module.
Returns:

true if success.

Simulation

bool ALVideoDeviceProxy::putImage(const int& CameraIndex, const int& Width, const int& Height, const AL::ALValue& ImageBuffer)

Loads Image into kernel circular buffer. Simulates acquisition of a new image by the virtual camera.

Parameters:
  • CameraIndex – Index of the camera in the video system.
  • Width – Width of the image buffer among 1280, 640, 320, 160.
  • Height – Height of the image buffer among 960, 480, 240, 120.
  • ImageBuffer – The image Buffer in Bitmap form (i.e. RGB 24bits).
Returns:

true if success.

AL::ALValue ALVideoDeviceProxy::getExpectedImageParameters(const int& CameraIndex)

Called by the simulator to know expected image parameters

Returns:ALValue of expected parameters: [int height, int width, int framerate]

Conversion

std::vector<float> ALVideoDeviceProxy::getAngularPositionFromImagePosition(const int& CameraIndex, const std::vector<float>& ImagePosition)

Returns position as angles relative to camera axis given a normalized position in the image.

Parameters:
  • CameraIndex – Index of the camera in the video system.
  • ImagePosition – normalized position in the image [0.0 - 1.0]
Returns:

corresponding angles values in radians.

std::vector<float> ALVideoDeviceProxy::getImagePositionFromAngularPosition(const int& CameraIndex, const std::vector<float>& AngularPosition)

Returns a normalized position in the image from a position expressed with camera angles in radians.

Parameters:
  • CameraIndex – Index of the camera in the video system.
  • AngularPosition – camera angle values in radians.
Returns:

corresponding normalized position in the image [0.0 - 1.0]

std::vector<float> ALVideoDeviceProxy::getAngularSizeFromImageSize(const int& CameraIndex, const std::vector<float>& ImageSize)

From a normalized size in the image, returns size expressed as angles in radian relative to camera axis.

Parameters:
  • CameraIndex – Index of the camera in the video system.
  • ImageSize – normalized position in the image [0.0 - 1.0]
Returns:

corresponding angles values in radians.

std::vector<float> ALVideoDeviceProxy::getImageSizeFromAngularSize(const int& CameraIndex, const std::vector<float>& AngularSize)

Returns a normalized size from a size expressed with camera angles in radians.

Parameters:
  • CameraIndex – Index of the camera in the video system.
  • AngularSize – camera angle values in radians.
Returns:

corresponding normalized position in the image [0.0 - 1.0]

std::vector<float> ALVideoDeviceProxy::getImageInfoFromAngularInfo(const int& CameraIndex, const std::vector<float>& AngularInfo)

Returns [X, Y, width, height] normalized info in the image from these info expressed as angles in radians (as returned by vision extractors).

Parameters:
  • CameraIndex – Index of the camera in the video system.
  • AngularInfo – camera angle values in radians.
Returns:

corresponding normalized position and size info: [X, Y, width, height].

std::vector<float> ALVideoDeviceProxy::getImageInfoFromAngularInfoWithResolution(const int& CameraIndex, const std::vector<float>& AngularInfo, const int& ResolutionIndex)

Returns [X, Y, width, height] info as pixels in the image from these info expressed as angles in radians (as returned by vision extractors).

Parameters:
  • CameraIndex – Index of the camera in the video system.
  • AngularInfo – camera angle values in radians.
  • ResolutionIndex – image resolution
Returns:

corresponding pixels position and size info: [X, Y, width, height].

Deprecated Methods

std::string ALVideoDeviceProxy::subscribe(const std::string& Name, const int& resolution, const int& colorSpace, const int& fps)

Subscribe to ALVideoDevice. When a Video Module registers to ALVideoDevice, a buffer of the requested image format is added to the buffers list. Returns the name under which the V.M. will be known from ALVideoDevice (useful when several V.M. try to subscribe using the same name, the 3rd one getting _3 added to its name for instance).

Deprecated since version 1.14: use ALVideoDeviceProxy::subscribeCamera() instead.

Parameters:
  • Name – Name of the subscribing module.
  • resolution – Resolution requested. (see resolution)
  • colorSpace – Colorspace requested. (see colorspace)
  • fps – Fps (frames per second) requested to the video source. The OV7670 VGA camera can only run at 30fps, the MT9M114 HD camera will be able to run faster with some special modes in a near future.
Returns:

Name under which the V.M. is known from ALVideoDevice, NULL if failed.

Note

Compared to a local module, the obtained framerate for a remote module will depend on the network available bandwith (e.g. we can reach raw 1280x960@10fps using a Gigabit Ethernet connection with the HD camera).

void ALVideoDeviceProxy::unsubscribeAllInstances(const std::string& Name)

Used to unsubscribe all instances for a given module (e.g. VisionModule and VisionModule_5) from ALVideoDevice.

Deprecated since version 1.14: use ALVideoDeviceProxy::unsubscribe() instead.

Parameters:
  • Name – Name of the subscribing module.
bool ALVideoDeviceProxy::startFrameGrabber()

Opens and initialize the video source device if it was not already opened.

Deprecated since version 1.14: use ALVideoDeviceProxy::startFrameGrabber() instead.

Note

The first module subscribing to ALVideoDevice will launch it automatically, so the main purpose of this method is to reduce time when the first vision module is subscribing.

Returns:true if success
bool ALVideoDeviceProxy::stopFrameGrabber()

Close the video source device.

Deprecated since version 1.14: use ALVideoDeviceProxy::stopFrameGrabber() instead.

Note

When the last vision module subscribed to ALVideoDevice unsubscribes, this doesn’t close the video source device as we assume that if some video was requested before, video will be again requested latter. But if this is not the case, closing the video source will save processing resources.

Returns:true if success
int ALVideoDeviceProxy::isFrameGrabberOff()

Asks if the framegrabber is running or not.

Deprecated since version 1.14: use ALVideoDeviceProxy::isFrameGrabberOff() instead.

Returns:true if off
int ALVideoDeviceProxy::getActiveCamera()

Gets the index of the current default active camera.

Deprecated since version 1.14: use ALVideoDeviceProxy::getActiveCamera() instead.

Returns:cameraindex.

alvideodevice_subscribe.cpp

#include <alproxies/alvideodeviceproxy.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_getactivecamera pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  int activeCam = cameraProxy.getActiveCamera();

  std::cout << "Active camera is " << activeCam << std::endl;
  return 0;
}
int ALVideoDeviceProxy::getVIMResolution()

Get the resolution of the video source before eventual conversion.

Deprecated since version 1.14: use ALVideoDeviceProxy::getResolution() instead.

Returns:{ 0 = kQQVGA, 1 = kQVGA, 2 = kVGA, 3 = k4VGA } -1: can’t access video source
int ALVideoDeviceProxy::getVIMColorSpace()

Get the color space of the video source before enventual conversion.

Deprecated since version 1.14: use ALVideoDeviceProxy::getColorSpace() instead.

Returns:{ 0 = kYuv, 9 = kYUV422, 10 = kYUV, 11 = kRGB, 12 = kHSY, 13 = kBGR } -1 can’t access video source
int ALVideoDeviceProxy::getVIMFrameRate()

Get the internal frame rate of the video source.

Deprecated since version 1.14: use ALVideoDeviceProxy::getFrameRate() instead.

Returns:video source framerate. -1: can’t access video source
int ALVideoDeviceProxy::getGVMResolution(const std::string& id)

Get the resolution of a particular Vision Module

Deprecated since version 1.14: use ALVideoDeviceProxy::getResolution() instead.

Parameters:
  • id – Name under which the V.M. is known from ALVideoDevice.
Returns:

resolution or -1: can’t access video source

int ALVideoDeviceProxy::getGVMColorSpace(const std::string& id)

Get the color space of a particular Vision Module.

Deprecated since version 1.14: use ALVideoDeviceProxy::getColorSpace() instead.

Parameters:
  • id – Name under which the V.M. is known from ALVideoDevice.
Returns:

colorspace -1: can’t access video source

int ALVideoDeviceProxy::getGVMFrameRate(const std::string& id)

Get the frame rate that a particular Vision Module has requested to the camera. This doesn’t mean the video source is able to run at this frame rate (see ALVideoDeviceProxy::getVIMFrameRate() to know the video source framerate). This doesn’t either mean that a remote module will obtain images at this framerate due to network bandwith limitations.

Deprecated since version 1.14: use ALVideoDeviceProxy::getFrameRate() instead.

Parameters:
  • id – Name under which the V.M. is known from ALVideoDevice.
Returns:

The Vision Module framerate, or -1 if we can’t access video source

int ALVideoDeviceProxy::getCameraModelID()

Gets the camera model index of the current default active camera.

Deprecated since version 1.14: use ALVideoDeviceProxy::getCameraModel() instead.

Returns:cameramodel.
int ALVideoDeviceProxy::getParam(const int& Param)

Get the value of a video source specific parameter.

Deprecated since version 1.14: use ALVideoDeviceProxy::getCameraParameter() instead.

Warning

Depending on the type of the video source, available parameters may change.

Parameters:
  • Param – Parameter’s reference. See below the parameters list according to the type of video source.
Returns:

Parameter’s value. See below the parameters list according to the type of video source (values are available in Modifying camera parameters ).

alvideodevice_getparam.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_getparam pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Example: retrieve the ID of the selected camera.
  int pVal = cameraProxy.getParam(AL::kCameraSelectID);
  std::cout << "AL::kCameraSelectID is " << pVal << std::endl;

  return 0;
}
void ALVideoDeviceProxy::setParam(const int& Param, const int& NewValue)

Sets the value of a specific parameter for the video source.

Deprecated since version 1.14: use ALVideoDeviceProxy::setCameraParameter() instead.

Parameters:
  • Param – Parameter’s reference. See below the parameters list according to the type of video source (values are available in Modifying camera parameters ).
  • NewValue – Parameter’s new value.

alvideodevice_setparam.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_setparam pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // For example, set the current selected camera to top camera.
  cameraProxy.setParam(AL::kCameraSelectID, 0);

  std::cout << "AL::kCameraSelectID has been set to " << 0 << std::endl;

  return 0;
}
void ALVideoDeviceProxy::setParamDefault(const int& Param)

Sets a specific parameter for the video source at its default value.

Deprecated since version 1.14: use ALVideoDeviceProxy::setCameraParameterToDefault() instead.

Parameters:
  • param – Parameter’s reference. See below the parameters list according to the type of video source (values are available in Modifying camera parameters ).

alvideodevice_setparamdefault.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

#include <iostream>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_setparamdefault pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // For example, set the current selected camera to default.
  cameraProxy.setParamDefault(AL::kCameraSelectID);

  std::cout << "AL::kCameraSelectID has been set to default value "
            << cameraProxy.getParam(AL::kCameraSelectID) << std::endl;

  return 0;
}
std::vector<float> ALVideoDeviceProxy::getAngPosFromImgPos(const std::vector<float>& imgPos)

Returns position as angles relative to camera axis given a normalized position in the image.

Deprecated since version 1.14: use ALVideoDeviceProxy::getAngularPositionFromImagePosition() instead.

Parameters:
  • imgPos – normalized position in the image [0.0 - 1.0]
Returns:

corresponding angles values in radians.

alvideodevice_subscribe.cpp

#include <iostream>
#include <vector>

#include <alproxies/alvideodeviceproxy.h>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_imagetoangle pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Example of a normalized position in the image.
  float x = 0.2f, y = 0.7f;
  std::vector<float> posUV;
  posUV.push_back(x);
  posUV.push_back(y);

  // Retrieve the corresponding angles.
  std::vector<float> camAngles = cameraProxy.getAngPosFromImgPos(posUV);
  std::cout << "Position " << posUV << " corresponds to angles "
            << camAngles << std::endl;

  // Example of a normalized object size.
  float sizeX = 0.1f, sizeY = 0.3f;
  posUV.clear();
  posUV.push_back(sizeX);
  posUV.push_back(sizeY);

  // Retrieve corresponding angle size.
  std::vector<float> angSize = cameraProxy.getAngSizeFromImgSize(posUV);
  std::cout << "Object size " << posUV << "corresponds to angle size "
            << angSize << std::endl;

  return 0;
}
std::vector<float> ALVideoDeviceProxy::getAngSizeFromImgSize(const std::vector<float>& imgSize)

From a normalized size in the image, returns size expressed as angles in radian relative to camera axis.

Deprecated since version 1.14: use ALVideoDeviceProxy::getAngularSizeFromImageSize() instead.

Parameters:
  • imgSize – normalized position in the image [0.0 - 1.0]
Returns:

corresponding angles values in radians.

alvideodevice_subscribe.cpp

#include <iostream>
#include <vector>

#include <alproxies/alvideodeviceproxy.h>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_imagetoangle pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Example of a normalized position in the image.
  float x = 0.2f, y = 0.7f;
  std::vector<float> posUV;
  posUV.push_back(x);
  posUV.push_back(y);

  // Retrieve the corresponding angles.
  std::vector<float> camAngles = cameraProxy.getAngPosFromImgPos(posUV);
  std::cout << "Position " << posUV << " corresponds to angles "
            << camAngles << std::endl;

  // Example of a normalized object size.
  float sizeX = 0.1f, sizeY = 0.3f;
  posUV.clear();
  posUV.push_back(sizeX);
  posUV.push_back(sizeY);

  // Retrieve corresponding angle size.
  std::vector<float> angSize = cameraProxy.getAngSizeFromImgSize(posUV);
  std::cout << "Object size " << posUV << "corresponds to angle size "
            << angSize << std::endl;

  return 0;
}
std::vector<float> ALVideoDeviceProxy::getImgInfoFromAngInfo(const std::vector<float>& angles)

Returns [X, Y, width, height] normalized info in the image from these info expressed as angles in radians (as returned by vision extractors).

Deprecated since version 1.14: use ALVideoDeviceProxy::getImageInfoFromAngularInfo() instead.

Parameters:
  • angles – camera angle values in radians.
Returns:

corresponding normalized position and size info: [X, Y, width, height].

std::vector<float> ALVideoDeviceProxy::getImgInfoFromAngInfoWithRes(const std::vector<float>& angInfo, const int& resIndex)

Returns [X, Y, width, height] info as pixels in the image from these info expressed as angles in radians (as returned by vision extractors).

Deprecated since version 1.14: use ALVideoDeviceProxy::getImageInfoFromAngularInfoWithResolution() instead.

Parameters:
  • angInfo – camera angle values in radians.
  • resIndex – image resolution
Returns:

corresponding pixels position and size info: [X, Y, width, height].

std::vector<float> ALVideoDeviceProxy::getImgPosFromAngPos(const std::vector<float>& angPos)

Returns a normalized position in the image from a position expressed with camera angles in radians.

Deprecated since version 1.14: use ALVideoDeviceProxy::getImagePositionFromAngularPosition() instead.

Parameters:
  • angPos – camera angle values in radians.
Returns:

corresponding normalized position in the image [0.0 - 1.0]

alvideodevice_angletoimage.cpp

#include <iostream>
#include <vector>

#include <alproxies/alvideodeviceproxy.h>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage videodevice_angletoimage pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Example camera angles.
  std::vector<float> camAngles;
  camAngles.push_back(0.1f);
  camAngles.push_back(0.1f);

  // Retrieve image position in pixels.
  std::vector<float> imgPos = cameraProxy.getImgPosFromAngPos(camAngles);
  std::cout << "Camera angles " << camAngles << " correspond to "
            << imgPos << " in pixels" << std::endl;

  camAngles.clear();
  // Example camera angle size.
  camAngles.push_back(0.1f);
  camAngles.push_back(0.3f);
  // Retrieve object size in pixels.
  std::vector<float> imSize = cameraProxy.getImgSizeFromAngSize(camAngles);
  std::cout << "Angle size " << imSize << " corresponds to "
            << imSize << " size in pixels" << std::endl;

  return 0;
}
std::vector<float> ALVideoDeviceProxy::getImgSizeFromAngSize(const std::vector<float>& angSize)

Returns a normalized size from a size expressed with camera angles in radians.

Deprecated since version 1.14: use ALVideoDeviceProxy::getImageSizeFromAngularSize() instead.

Parameters:
  • angSize – camera angle values in radians.
Returns:

corresponding normalized position in the image [0.0 - 1.0]

alvideodevice_subscribe.cpp

#include <iostream>
#include <vector>

#include <alproxies/alvideodeviceproxy.h>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage videodevice_angletoimage pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Example camera angles.
  std::vector<float> camAngles;
  camAngles.push_back(0.1f);
  camAngles.push_back(0.1f);

  // Retrieve image position in pixels.
  std::vector<float> imgPos = cameraProxy.getImgPosFromAngPos(camAngles);
  std::cout << "Camera angles " << camAngles << " correspond to "
            << imgPos << " in pixels" << std::endl;

  camAngles.clear();
  // Example camera angle size.
  camAngles.push_back(0.1f);
  camAngles.push_back(0.3f);
  // Retrieve object size in pixels.
  std::vector<float> imSize = cameraProxy.getImgSizeFromAngSize(camAngles);
  std::cout << "Angle size " << imSize << " corresponds to "
            << imSize << " size in pixels" << std::endl;

  return 0;
}
AL::ALValue ALVideoDeviceProxy::getExpectedImageParameters()

Called by the simulator to know expected image parameters

Deprecated since version 1.14: use ALVideoDeviceProxy::getExpectedImageParameters() instead.

Returns:ALValue of expected parameters: [int height, int width, int framerate]
bool ALVideoDeviceProxy::setSimCamInputSize(const int& Width, const int& Height)

Set parameters for the images that the simulator will provide.

Deprecated since version 1.14: use ALVideoDeviceProxy::putImage() instead.

Parameters:
  • Width – width of images among 1280, 640, 320, 160
  • Height – height of images among 960, 480, 240, 120
Returns:

true if success

bool ALVideoDeviceProxy::putImage(const AL::ALValue& ImageBuffer)

Allow image buffer pushing

Deprecated since version 1.14: use ALVideoDeviceProxy::putImage() instead.

Parameters:
  • ImageBuffer – The image buffer in bitmap form
Returns:

true if success

AL::ALValue ALVideoDeviceProxy::resolutionToSizes(const int& Resolution)

return the width and the height of a resolution

Deprecated since version 1.14: use AL::setSizeFromResolution instead. For further details, see: libalvision API reference.

Parameters:
  • resolution – { 0 = kQQVGA, 1 = kQVGA, 2 = kVGA }
Returns:

array of sizes: (return [-1;-1] if the format is invalid) [0] : width; [1] : height;

alvideodevice_resolutiontosizes.cpp

#include <iostream>

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage videodevice_resolutiontosizes pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Retrieve current image size.
  AL::ALValue size = cameraProxy.resolutionToSizes(AL::kVGA);
  std::cout << "Image width is " << size[0] << " and image height is "
            << size[1] << std::endl;

  return 0;
}
int ALVideoDeviceProxy::sizesToResolution(const int& Width, const int& Height)

return the resolution from sizes

Deprecated since version 1.14: use AL::getResolutionFromSize instead. For further details, see: libalvision API reference.

Parameters:
  • width – width of the image
  • height – height of the image
Returns:

resolution or -1 if the inputs are invalid

alvideodevice_siizestoresolution.cpp

#include <iostream>

#include <alproxies/alvideodeviceproxy.h>
#include <alvision/alvisiondefinitions.h>

int main(int argc, char **argv)
{
  if (argc < 2) {
    std::cerr << "Usage: videodevice_sizestoresolution pIp" << std::endl;
    return 1;
  }
  const std::string pIp = argv[1];

  // Proxy to ALVideoDevice.
  AL::ALVideoDeviceProxy cameraProxy(pIp);

  // Get resolution of the currently selected camera.
  int resolution = cameraProxy.sizesToResolution(640, 480);

  switch(resolution) {
  case 0:
    std::cout << "Current resolution is QQVGA" << std::endl;
    break;

  case 1:
    std::cout << "Current resolution is QVGA" << std::endl;
    break;

  case 2:
    std::cout << "Current resolution is VGA" << std::endl;
    break;

  default:
    std::cerr << "Unknown resolution" << std::endl;
    break;
  }

  return 1;
}

Internal Types

Camera Index

Camera Index can have the following values:

Parameter ID Name ID Value Description
AL::kTopCamera 0 camera on the top.
AL::kBottomCamera 1 camera on the bottom.

Camera Model

Camera Model can have the following values:

Parameter ID Name ID Value Description
AL::kOV7670 1 VGA Camera
AL::kMT9M114 2 HD Camera

Resolution

Resolution parameter can have the following values:

Parameter ID Name ID Value Description
AL::kQQVGA 0 Image of 160*120px
AL::kQVGA 1 Image of 320*240px
AL::kVGA 2 Image of 640*480px
AL::k4VGA 3 Image of 1280*960px

Note

AL::k4VGA is only available on NAO V4 (camera HD MT9M114).

Color Space

A color space is a model describing the way to represent color as an ordered list of numbers. For example you can represent the color of each pixel of your screen as a list of three elements R, G and B. Which are respectively the value of Red, Green, and Blue usually store in an byte (range from 0 to 255).

Setting the color space allows you to set the image buffer encoding in AL::ALImage.

Color space parameter can have the following values:

Parameter ID Name ID Value Number of channels Description
AL::kYuvColorSpace 0 1 Buffer only contains the Y (luma component) equivalent to one unsigned char
AL::kyUvColorSpace 1 1 Buffer only contains the U (Chrominance component) equivalent to one unsigned char
AL::kyuVColorSpace 2 1 Buffer only contains the V (Chrominance component) equivalent to one unsigned char
AL::kRgbColorSpace 3 1 Buffer only contains the R (Red component) equivalent to one unsigned char
AL::krGbColorSpace 4 1 Buffer only contains the G (Green component) equivalent to one unsigned char
AL::krgBColorSpace 5 1 Buffer only contains the B (Blue component) equivalent to one unsigned char
AL::kHsyColorSpace 6 1 Buffer only contains the H (Hue component) equivalent to one unsigned char
AL::khSyColorSpace 7 1 Buffer only contains the S (Saturation component) equivalent to one unsigned char
AL::khsYColorSpace 8 1 Buffer only contains the Y (Brithness component) equivalent to one unsigned char
AL::kYUV422ColorSpace 9 3 Native format, 0xY’Y’VVYYUU equivalent to four unsigned char for two pixels. With Y luma for pixel n, Y’ luma for pixel n+1, and U and V are the average chrominance value of both pixels.
AL::kYUVColorSpace 10 3 Buffer contains triplet on the format 0xVVUUYY, equivalent to three unsigned char
AL::kRGBColorSpace 11 3 Buffer contains triplet on the format 0xBBGGRR, equivalent to three unsigned char
AL::kHSYColorSpace 12 3 Buffer contains triplet on the format 0xYYSSHH, equivalent to three unsigned char
AL::kBGRColorSpace 13 3 Buffer contains triplet on the format 0xRRGGBB, equivalent to three unsigned char
AL::kYYCbCrColorSpace 14 3 TIFF format, four unsigned chararacters for two pixels.
AL::kH2RGBColorSpace 15 3 H from “HSY to RGB” in fake colors.
AL::kHSMixedColorSpace 16 3 HS and (H+S)/2.

Frame Rate

The OV7670 VGA camera can only run at 30, 15, 10 and 5fps (frame per second). On the contrary MT9M114 HD camera will be able to run from 1 to 30fps.

Note

On camera OV7670, the framerate is automaticaly set to the upper closest available frmae rate. (e.g. if you set framerate to 12, it will be setup to 15 internaly)

Image

Image container is an array as follow:

  • [0]: width.
  • [1]: height.
  • [2]: number of layers.
  • [3]: ColorSpace.
  • [4]: time stamp (seconds).
  • [5]: time stamp (micro-seconds).
  • [6]: array of size height * width * nblayers containing image data.
  • [7]: camera ID (kTop=0, kBottom=1).
  • [8]: left angle (radian).
  • [9]: topAngle (radian).
  • [10]: rightAngle (radian).
  • [11]: bottomAngle (radian).

Images

Images container is an array of arrays as follow:

  • [0] First Image, an array containing:
    • [0]: width.
    • [1]: height.
    • [2]: number of layers.
    • [3]: ColorSpace.
    • [4]: time stamp (seconds).
    • [5]: time stamp (micro-seconds).
    • [6]: array of size height * width * nblayers containing image data. Currently a NULL pointer due to SOAP issue.
    • [7]: camera ID (kTop=0, kBottom=1).
    • [8]: left angle (radian).
    • [9]: topAngle (radian).
    • [10]: rightAngle (radian).
    • [11]: bottomAngle (radian).
  • [1] Second Image (with the same layout that the previous one).
  • [...]
  • [X] Xth Image.
  • [X+1] Buffer containing all image data concatened.