ALVideoDevice API

Overview | API | Tutorial | ALVideoDevice - Advanced

Namespace : AL

#include <alproxies/alvideodeviceproxy.h>

Method list

class ALVideoDeviceProxy

See also

Main Methods

std::string ALVideoDeviceProxy::subscribe(const std::string& vmName, 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).

Parameters:
  • vmName – Name of the subscribing V.M.
  • resolution – Resolution requested. { 0 = kQQVGA, 1 = kQVGA, 2 = kVGA, 3 = k4VGA }
  • colorSpace – Colorspace requested. { 0 = kYuv, 9 = kYUV422, 10 = kYUV, 11 = kRGB, 12 = kHSY, 13 = kBGR }
  • 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. 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).
Returns:

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

samples/cpp/alvideodevice/alvideodevice_subscribe.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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::unsubscribe(const std::string& pName)

Used to unsubscribe a V.M. from ALVideoDevice.

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

samples/cpp/alvideodevice/alvideodevice_subscribe.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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::unsubscribeAllInstances(const std::string& pName)

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

Parameters:
  • pName – Root name of the V.M. (e.g. with the example above this will be VisionModule).
void* ALVideoDeviceProxy::getImageLocal(const std::string& id)

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

Warning

When the image is not necessary anymore, a call to releaseImage() is requested. If the V.M. didn’t release the previous image, returns NULL.

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

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

Warning

Image pointer is valid only if your module is running locally, not for remote modules.

samples/cpp/alvideodevice/alvideodevice_imagelocal.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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& id)

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:
  • id – Name under which the V.M. is known from ALVideoDevice.
Returns:

Array containing image informations:

  • [0] : width;
  • [1] : height;
  • [2] : number of layers;
  • [3] : ColorSpace;
  • [4] : timestamp (seconds);
  • [5] : timestamp (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);

samples/cpp/alvideodevice/alvideodevice_imageremote.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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;
}
int ALVideoDeviceProxy::releaseImage(const std::string& id)

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

Parameters:
  • id – Name under which the V.M. is known from ALVideoDevice.
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).

samples/cpp/alvideodevice/alvideodevice_imagelocal.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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;
}
int ALVideoDeviceProxy::getParam(const int& pParam)

Get the value of a video source specific parameter.

Warning

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

Parameters:
  • pParam – 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 ).

video source: OV7670 VGA camera

  • kCameraSetDefaultParamsID,
  • kCameraSelectID,
  • kCameraFastSwitchID (advanced function that needs both camera to run same format. Parameter value has no signification),
  • kCameraResolutionID (possible resolutions for the video source, not as requested by a Vision Module; e.g. QQVGA isn’t provided directly by the camera),
  • kCameraHFlipID,
  • kCameraVFlipID,
  • kCameraBrightnessID,
  • kCameraContrastID,
  • kCameraSaturationID,
  • kCameraHueID,
  • kCameraSharpnessID (0-1: no sharpness - 2: medium sharpness - 3-5: high sharpness - higher: cartoon effect),
  • kCameraAutoWhiteBalanceID,
  • kCameraRedChromaID,
  • kCameraBlueChromaID,
  • kCameraAutoExpositionID,
  • kCameraExposureID,
  • kCameraAutoGainID,
  • kCameraGainID,
  • kCameraExposureCorrectionID (correction by n/3 IL, switch automatically in average-based AEC algorithm if n!=0 and back to histogram-based for n=0),
  • kCameraAecAlgorithmID,
  • kCameraAwbGreenGainID,
  • kCameraAblcID,
  • kCameraAblcTargetID,
  • kCameraAblcStableRangeID,
  • kCameraBlcBlueID,
  • kCameraBlcRedID,
  • kCameraBlcGbID,
  • kCameraBlcGrID,

video source: MT9M114 HD camera

  • kCameraSetDefaultParamsID,
  • kCameraSelectID,
  • kCameraResolutionID (possible resolutions for the video source, not as requested by a Vision Module; e.g. QQVGA isn’t provided directly by the camera),
  • kCameraHFlipID,
  • kCameraVFlipID,
  • kCameraBrightnessID,
  • kCameraContrastID,
  • kCameraSaturationID,
  • kCameraHueID,
  • kCameraSharpnessID
  • kCameraAutoWhiteBalanceID,
  • kCameraWhiteBalanceID,
  • kCameraAutoExpositionID,
  • kCameraExposureID,
  • kCameraGainID,
  • kCameraBacklightCompensationID

video source: simulatorcam

  • kCameraResolutionID,
  • kCameraSelectID

video source: filecam

  • kCameraResolutionID,
  • kCameraSelectID

samples/cpp/alvideodevice/alvideodevice_getparam.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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.

Parameters:
  • param

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

    video source: OV7670 VGA camera

    • kCameraSetDefaultParamsID,
    • kCameraSelectID,
    • kCameraFastSwitchID (advanced function that needs both camera to run same format. Parameter value has no signification),
    • kCameraResolutionID (possible resolutions for the video source, not as requested by a Vision Module; e.g. QQVGA isn’t provided directly by the camera),
    • kCameraHFlipID,
    • kCameraVFlipID,
    • kCameraBrightnessID,
    • kCameraContrastID,
    • kCameraSaturationID,
    • kCameraHueID,
    • kCameraSharpnessID (0-1: no sharpness - 2: medium sharpness - 3-5: high sharpness - higher: cartoon effect)
    • kCameraAutoWhiteBalanceID,
    • kCameraRedChromaID,
    • kCameraBlueChromaID,
    • kCameraAutoExpositionID,
    • kCameraExposureID,
    • kCameraAutoGainID,
    • kCameraGainID,
    • kCameraExposureCorrectionID (correction by n/3 IL, switch automatically in average-based AEC algorithm if n!=0 and back to histogram-based for n=0),
    • kCameraAecAlgorithmID,
    • kCameraAwbGreenGainID,
    • kCameraAblcID,
    • kCameraAblcTargetID,
    • kCameraAblcStableRangeID,
    • kCameraBlcBlueID,
    • kCameraBlcRedID,
    • kCameraBlcGbID,
    • kCameraBlcGrID,

    Note

    The disabled camera will get back to auto gain/exposure/white balance settings after a while. This is a camera issue when it is freezed.

    Note

    Fast switch usually switchs between cameras in 66ms (33ms for waked up sensor exposure + 33ms for data transfer) after previous image completion. However, sometimes we can observe a clipped image from the former camera after 66ms. This is an electronical issue and so we suggest to considere only images after 100ms

    video source: MT9M114 HD camera

    • kCameraSetDefaultParamsID,
    • kCameraSelectID,
    • kCameraResolutionID (possible resolutions for the video source, not as requested by a Vision Module; e.g. QQVGA isn’t provided directly by the camera),
    • kCameraHFlipID,
    • kCameraVFlipID,
    • kCameraBrightnessID,
    • kCameraContrastID,
    • kCameraSaturationID,
    • kCameraHueID,
    • kCameraSharpnessID,
    • kCameraAutoWhiteBalanceID,
    • kCameraWhiteBalanceID,
    • kCameraAutoExpositionID,
    • kCameraExposureID,
    • kCameraGainID,
    • kCameraBacklightCompensationID

    video source: simulatorcam

    • kCameraResolutionID,
    • kCameraSelectID

    video source: filecam

    • kCameraResolutionID,
    • kCameraSelectID
  • newValue – Parameter’s new value.

samples/cpp/alvideodevice/alvideodevice_setparam.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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.

Parameters:
  • param

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

    video source: OV7670 VGA camera

    • kCameraSetDefaultParamsID,
    • kCameraSelectID,
    • kCameraFastSwitchID (advanced function that needs both camera to run same format. Parameter value has no signification),
    • kCameraResolutionID (possible resolutions for the video source, not as requested by a Vision Module; e.g. QQVGA isn’t provided directly by the camera),
    • kCameraHFlipID,
    • kCameraVFlipID,
    • kCameraBrightnessID,
    • kCameraContrastID,
    • kCameraSaturationID,
    • kCameraHueID,
    • kCameraSharpnessID (0-1: no sharpness - 2: medium sharpness - 3-5: high sharpness - higher: cartoon effect)
    • kCameraAutoWhiteBalanceID,
    • kCameraRedChromaID,
    • kCameraBlueChromaID,
    • kCameraAutoExpositionID,
    • kCameraExposureID,
    • kCameraAutoGainID,
    • kCameraGainID,
    • kCameraExposureCorrectionID (correction by n/3 IL, switch automatically in average-based AEC algorithm if n!=0 and back to histogram-based for n=0),
    • kCameraAecAlgorithmID,
    • kCameraAwbGreenGainID,
    • kCameraAblcID,
    • kCameraAblcTargetID,
    • kCameraAblcStableRangeID,
    • kCameraBlcBlueID,
    • kCameraBlcRedID,
    • kCameraBlcGbID,
    • kCameraBlcGrID,

    video source: MT9M114 HD camera

    • kCameraSetDefaultParamsID,
    • kCameraSelectID,
    • kCameraResolutionID (possible resolutions for the video source, not as requested by a Vision Module; e.g. QQVGA isn’t provided directly by the camera),
    • kCameraHFlipID,
    • kCameraVFlipID,
    • kCameraBrightnessID,
    • kCameraContrastID,
    • kCameraSaturationID,
    • kCameraHueID,s
    • kCameraSharpnessID,
    • kCameraAutoWhiteBalanceID,
    • kCameraWhiteBalanceID,
    • kCameraAutoExpositionID,
    • kCameraExposureID,
    • kCameraGainID,
    • kCameraBacklightCompensationID

    video source: simulatorcam

    • kCameraResolutionID,
    • kCameraSelectID

    video source: filecam

    • kCameraResolutionID,
    • kCameraSelectID

samples/cpp/alvideodevice/alvideodevice_setparamdefault.cpp

#include <alproxies/alvideodeviceproxy.h>
#include <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;
}
bool ALVideoDeviceProxy::setResolution(const std::string& id, const int& size)

Change the resolution requested by a Vision Module

Parameters:
  • id – Name under which the V.M. is known from ALVideoDevice.
  • size
    • video source OV7670 VGA camera: { 0 = kQQVGA, 1 = kQVGA, 2 = kVGA }
    • video source MT9M114 HD camera: { 0 = kQQVGA, 1 = kQVGA, 2 = kVGA, 3 = k4VGA (1280x960) }
    • video source simulatorcam: { 0 = kQQVGA, 1 = kQVGA, 2 = kVGA }
    • video source filecam: any resolution smaller or equal to the one of the images in the file (accessible with getVIMResolution).
Returns:

true if success

bool ALVideoDeviceProxy::setColorSpace(const std::string& id, const int& colorSpace)

Change the colorspace requested by a Vision Module.

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

    Parameter’s reference among

    • kYuvColorSpace = 0;
    • kyUvColorSpace = 1;
    • kyuVColorSpace = 2;
    • kRgbColorSpace = 3;
    • krGbColorSpace = 4;
    • krgBColorSpace = 5;
    • kHsyColorSpace = 6;
    • khSyColorSpace = 7;
    • khsYColorSpace = 8;
    • kYUV422ColorSpace = 9;
    • kYUVColorSpace = 10;
    • kRGBColorSpace = 11;
    • kHSYColorSpace = 12;
    • kBGRColorSpace = 13; // for using with opencv
    • kYYCbCrColorSpace = 14; // for tiff implementation
    • kH2RGBColorSpace = 15; // H from “HSY to RGB” in fake colors
    • kHSMixedColorSpace = 16; // HS and (H +S)/2
Returns:

true if success

bool ALVideoDeviceProxy::setFrameRate(const std::string& id, const int& frameRate)

Change the framerate requested to the video source by the Vision Module.

Parameters:
  • id – Name under which the V.M. is known from ALVideoDevice.
  • frameRate – images per seconds. 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:

true if success

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

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

Get the resolution of a particular Vision Module

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

{ 0 = kQQVGA, 1 = kQVGA, 2 = kVGA, 3 = k4VGA } -1: can’t access video source

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

Get the color space of a particular Vision Module.

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

-1: can’t access video source

  • kYuvColorSpace = 0;
  • kyUvColorSpace = 1;
  • kyuVColorSpace = 2;
  • kRgbColorSpace = 3;
  • krGbColorSpace = 4;
  • krgBColorSpace = 5;
  • kHsyColorSpace = 6;
  • khSyColorSpace = 7;
  • khsYColorSpace = 8;
  • kYUV422ColorSpace = 9;
  • kYUVColorSpace = 10;
  • kRGBColorSpace = 11;
  • kHSYColorSpace = 12;
  • kBGRColorSpace = 13; // for using with opencv
  • kYYCbCrColorSpace = 14; // for tiff implementation
  • kH2RGBColorSpace = 15; // H from “HSY to RGB” in fake colors
  • kHSMixedColorSpace = 16; // HS and (H +S)/2

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.

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::sizesToResolution(const int& width, const int& height)

return the resolution from sizes

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

{ 0 = kQQVGA, 1 = kQVGA, 2 = kVGA, 3 = k4VGA } or -1 if the inputs are invalid

samples/cpp/alvideodevice/alvideodevice_sizestoresolution.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;
}
AL::ALValue ALVideoDeviceProxy::resolutionToSizes(const int& resolution)

return the width and the height of a resolution

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

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

samples/cpp/alvideodevice/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;
}

Video recording and replaying methods

bool ALVideoDeviceProxy::recordVideo(const std::string& id, const std::string& path, const int& totalNumber, const int& period)

BETA - background record of an .arv raw format video from the images processed by a Vision Module

Parameters:
  • id – Name under which the V.M. is known from ALVideoDevice
  • 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

samples/python/alvideodevice/getImageLocal_and_recordArv.py

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& id)

BETA - stop writing the video sequence

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

true if success

void* ALVideoDeviceProxy::setVideo(const std::string& filePath, const AL::ALValue& range, const bool& loop, const int& replayMode, const int& streamNumber)

BETA - Set the parameters to play a video.

Parameters:
  • filePath – Name with the absolute path of the arv video file to replay
  • range – If set to NULL the complete file will be replayed. If an array is provided (e.g. [3, 142]), only frames in that range will be replayed.
  • loop – Loop if set to true.
  • replayMode

    Controls the replay mode :

    • 0 replay frame per frame (using nextImage/previousImage) if replaySpeed is set to 0, or at a frame rate defined by the user.
    • 1 replay tries to comply with original image acquisition timestamp intervals (vision modules will lose frames if their process is too. long).
  • streamNumber – for multi stream videos, select which stream to play. Default should be 0.
Return :

true if success

samples/python/alvideodevice/replayArvVideo.py

from naoqi import ALProxy


IP = "127.0.0.1"  # Put here the IP address of your NAOqi
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)

pRange = [0,10000]
pLoop = True
pReplayMode = 0
pStreamNumber = 0

try:
  camProxy.setVideo("/home/nao/myVideo.arv", pRange, pLoop, pReplayMode, pStreamNumber)
except Exception,e:
  print "setVideo Failed"

print 'end of script'
void* ALVideoDeviceProxy::replaySpeed(const std::vector<float>& imagesPerSecond)

BETA - When replaying in mode 0, set the speed for replaying the video sequence.

Parameters:
  • imagesPerSecond – Set the desired images per second. O will act like if the video source was always sending the same image.
void* ALVideoDeviceProxy::previousImage()

BETA - When replaying in mode 0, ask for the previous image.

void* ALVideoDeviceProxy::nextImage()

BETA - When replaying in mode 0, ask for the next image.

int ALVideoDeviceProxy::getCurrentImageNumber()

BETA - Ask for the position of the current image in the sequence.

Returns:Returns the index of the current image.

Video source parameters

int ALVideoDeviceProxy::getActiveCamera()

Get the active camera ID

Returns:
  • 0: top camera
  • 1: bottom camera

samples/cpp/alvideodevice/alvideodevice_getactivecamera.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::getVIMColorSpace()

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

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.

Returns:video source framerate. -1: can’t access video source
int ALVideoDeviceProxy::getVIMResolution()

Get the resolution of the video source before eventual conversion.

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

Angles management

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.

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

corresponding angles values in radians.

samples/cpp/alvideodevice/alvideodevice_imagetoangle.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.

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

corresponding angles values in radians.

samples/cpp/alvideodevice/alvideodevice_imagetoangle.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).

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

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.

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

corresponding normalized position in the image [0.0 - 1.0]

samples/cpp/alvideodevice/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.

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

corresponding normalized position in the image [0.0 - 1.0]

samples/cpp/alvideodevice/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;
}

Advanced methods

int ALVideoDeviceProxy::startFrameGrabber()

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.
Returns:true if success
int ALVideoDeviceProxy::stopFrameGrabber()

Close 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.
Returns:true if success
int ALVideoDeviceProxy::isFrameGrabberOff()

Asks if the framegrabber is running or not.

Returns:true if off
void* ALVideoDeviceProxy::getDirectRawImageLocal(const std::string& id)

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

Warning

When image is not necessary anymore, a call to releaseDirectRawImage() is requested.

Warning

When using this mode for several vision modules, if they need raw data for more than 25ms check that you have strictly less V.M. in this requesting direct raw images than the amount of kernel buffers.

Warning

Release all kernel buffers (using releaseDirectRawImage) before doing any action requesting a modification of the video source mode (e.g. resolution, switch between cameras).

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

Pointer to the locked image buffer, NULL if error.

Warning

Image pointer is valid only for local modules. For remote modules, the address space is different from the one of NAOqi.

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

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

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

Array containing image informations:

  • [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);

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

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

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

true if success

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.

Simulator methods

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

Allow image buffer pushing

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

true if success

AL::ALValue& ALVideoDeviceProxy::getExpectedImageParameters()

Called by the simulator to know expected image parameters

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.

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

true if success