Aldebaran documentation What's new in NAOqi 2.4.3?

ALVideoDevice API

NAOqi Vision - Overview | API


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

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 an handle which identifies the module in ALVideoDevice. (This handle is based on the name parameter,e.g. the 3rd one getting _3 added to its name for instance to build this handle).

Parameters:
Returns:

String handle under which the module is known from ALVideoDevice, empty string if error occurred.

Warning

The same Name could be used only six time.

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

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 Input System. When a Video Module subscribes to ALVideoDevice, a buffer of the requested image resolution is added to the list of buffers for each camera.

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

String handle under which the module is known from ALVideoDevice.

Warning

The same Name could be used only six time.

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.
bool ALVideoDeviceProxy::unsubscribe(const std::string& Handle)

Unregisters a module from ALVideoDevice.

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

true if success, false otherwise.

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;
}
AL::ALValue ALVideoDeviceProxy::getSubscribers()

Gets a list containing all the handle name of the subscribers.

Returns:Array of string containing the subscriber names.

Camera Management

AL::ALValue ALVideoDeviceProxy::getCameraIndexes()

Gets list of available camera indexes.

Returns:Array of camera index (see Camera Indexes).
bool ALVideoDeviceProxy::hasDepthCamera()

Asks if a depth camera was detected by ALVideoDevice. If present, a depth camera can be accessed with the index kDepthCamera.

Returns:true if a depth camera is present, false otherwise.
int ALVideoDeviceProxy::getCameraModel(const int& CameraIndex)

Gets the camera model of the specified camera.

Parameters:
  • CameraIndex

    Index of the camera in the video system.

    For further details, see: Camera Indexes.

Returns:

Camera model.

std::string ALVideoDeviceProxy::getCameraName(const int& CameraIndex)

Gets the name of the specified camera.

Parameters:
  • CameraIndex – Index of the camera in the video system (see Camera Indexes).
Returns:

name of the camera (sensor name used by motion).

int ALVideoDeviceProxy::getActiveCamera()

Gets the index of the current default active camera.

Returns:Camera Indexes.

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;
}
bool ALVideoDeviceProxy::setActiveCamera(const int& ActiveCamera)

Sets the current default active camera for the system.

Parameters:
Returns:

true if success, false otherwise.

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 (see Camera Indexes).
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 (see Camera Indexes).
Returns:

Supported resolutions or -1: can’t access video source.

int ALVideoDeviceProxy::getColorSpace(const int& CameraIndex)

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

Parameters:
  • CameraIndex – Index of the camera in the video system (see Camera Indexes).
Returns:

Supported colorspaces or -1: can’t access video source.

float ALVideoDeviceProxy::getHorizontalFOV(const int& CameraIndex)

Gets the camera horizontal field of view for the specified camera.

Parameters:
  • CameraIndex – Index to the camera in the video system (see Camera Indexes).
Returns:

Horizontal field of view of the camera (in radian).

float ALVideoDeviceProxy::getVerticalFOV(const int& CameraIndex)

Gets the camera vertical field of view for the specified camera.

Parameters:
  • CameraIndex – Index to the camera in the video system (see Camera Indexes).
Returns:

Vertical field of view of the camera (in radian).

int ALVideoDeviceProxy::getParameter(const int& CameraIndex, const int& parameter)

Gets camera internal parameter.

Parameters:
Returns:

Value of the camera parameter.

AL::ALValue ALVideoDeviceProxy::getParameterRange(const int& CameraIndex, const int& Id)

Gets the range of a camera’s parameter.

Parameters:
Returns:

An ALValue containing the minimum and maximum value for the requested parameter.

bool ALVideoDeviceProxy::setParameter(const int& CameraIndex, const int& parameter, const int& newValue)

Modifies camera internal parameter.

Parameters:
  • CameraIndex – index to the camera whose module wants image (see Camera Indexes).
  • parameter – Id of the camera parameter (see Camera parameters).
  • newValue – value to set.
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::setParameterToDefault(const int& CameraIndex, const int& parameter)

Resets camera internal parameter to its default value.

Parameters:
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::setAllParametersToDefault(const int& CameraIndex)

Resets all camera internal parameters to their default value.

Parameters:
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::openCamera(const int& CameraIndex)

Opens and initializes the video source device.

Parameters:
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::closeCamera(const int& CameraIndex)

Closes the video source device, releasing resources.

Parameters:
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::isCameraOpen(const int& CameraIndex)

Detects if the video device is open (i.e. locked).

Parameters:
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::startCamera(const int& CameraIndex)

Starts the video capture of the specified video device.

Parameters:
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::stopCamera(const int& CameraIndex)

Stops the video capture of the specified video device.

Parameters:
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::isCameraStarted(const int& CameraIndex)

Detects if the video device is running (i.e. capture images).

Parameters:
Returns:

true if success, false otherwise.

Mono Stream Management

int ALVideoDeviceProxy::getActiveCamera(const std::string& Handle)

Gets the current active camera for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

Camera Indexes or -1: can’t access video source.

bool ALVideoDeviceProxy::setActiveCamera(const std::string& Handle, const int& ActiveCamera)

Sets the current active camera for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
  • ActiveCamera – Camera index (see Camera Indexes).
Returns:

true if success, false otherwise.

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

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:
  • Handle – Handle to identify the subscriber.
Returns:

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

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
  • Fps – Fps (frames per second) requested to the video source (see Supported framerates).

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, false otherwise.
int ALVideoDeviceProxy::getResolution(const std::string& Handle)

Gets the current resolution requested for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

Supported resolutions.

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
  • Resolution – Resolution requested (see Supported resolutions).
Returns:

true if success, false otherwise.

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

Gets the current color space requested for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

Supported colorspaces or -1: can’t access video source.

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

Sets the current color space requested for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
  • ColorSpace – Colorspace requested (see Supported colorspaces).
Returns:

true if success, false otherwise.

int ALVideoDeviceProxy::getCameraParameter(const std::string& Handle, 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:
  • Handle – Handle to identify the subscriber.
  • Id – Id of the camera parameter (see Camera parameters).
Returns:

Parameter’s value.

AL::ALValue ALVideoDeviceProxy::getCameraParameterRange(const std::string& Handle, const int& Id)

Gets the range of a camera’s parameter from the module current active camera.

Parameters:
  • Handle – Handle under which the module is known from the video system.
  • Id – Id of the camera parameter (see Camera parameters).
Returns:

An ALValue containing the minimum and maximum of the requested parameter.

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
  • Id – Id of the camera parameter (see Camera parameters).
  • NewValue – New value to set.
Returns:

true if success, false otherwise.

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

Sets a camera’s parameter to its default value.

Parameters:
  • Handle – Handle to identify the subscriber.
  • Id – Id of the camera parameter (see Camera parameters).
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::setAllCameraParametersToDefault(const std::string& Handle)

Resets all camera internal parameters to their default value.

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

true if successful, false otherwise.

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

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:
  • Handle – Handle to identify the subscriber.
Returns:

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

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

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:
  • Handle – Handle to identify the subscriber.
Returns:

Container of image.

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

true if success

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

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:
  • Handle – Handle to identify the subscriber.
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& Handle)

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:
  • Handle – Handle to identify the subscriber.
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& Handle)

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

Parameters:
  • Handle – Handle to identify the subscriber.
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

AL::ALValue ALVideoDeviceProxy::getActiveCameras(const std::string& Handle)

Gets current active cameras for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

Array of camera indexes (see Camera Indexes) or -1: can’t access video source.

AL::ALValue ALVideoDeviceProxy::setActiveCameras(const std::string& Handle, const AL::ALValue& ActiveCameras)

Sets the current active cameras for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
  • ActiveCameras – Array of the requested camera indexes (see Camera Indexes).
Returns:

Array of booleans with true if success.

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

Gets the current resolutions requested for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

Array of resolutions (see Supported resolutions).

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
  • Resolution – Array of resolutions requested (see Supported resolutions).
Returns:

Array of booleans with true if success.

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

Gets the current color spaces requested for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

Array of color spaces (see Supported colorspaces).

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

Sets the current color spaces requested for the specified module.

Parameters:
  • Handle – Handle to identify the subscriber.
  • ColorSpaces – Array of color spaces requested (see Supported colorspaces).
Returns:

Array of booleans with true if success

AL::ALValue ALVideoDeviceProxy::getCamerasParameter(const std::string& Handle, 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:
  • Handle – Handle to identify the subscriber.
  • Id – Id of the cameras parameter (see Camera parameters).
Returns:

Parameter’s values.

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
  • Id – Id of the camera parameter (see Camera parameters).
  • NewValue – New value to set.
Returns:

Array of booleans with true if success.

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

Sets a camera’s parameter to its default value.

Parameters:
  • Handle – Handle to identify the subscriber.
  • Id – Id of the camera parameter (see Camera parameters).
Returns:

Array of booleans with true if success.

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

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:
  • Handle – Handle to identify the subscriber.
Returns:

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

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

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:
  • Handle – Handle to identify the subscriber.
Returns:

Container of images.

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
Returns:

true if success

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

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:
  • Handle – Handle to identify the subscriber.
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& Handle)

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:
  • Handle – Handle to identify the subscriber.
Returns:

Container of images.

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

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

Parameters:
  • Handle – Handle to identify the subscriber.
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).

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 (see Camera Indexes).
  • 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, false otherwise.

Warning

This method only works in simulation.

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

Called by the simulator to know expected image parameters

Parameters:
  • CameraIndex – Index of the camera in the video system (see Camera Indexes).
Returns:

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

Warning

This method only works in simulation.

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 (see Camera Indexes).
  • ImagePosition – Vector of size 2 containing the normalized position along the horizontal and vertical dimensions of the image. The two values must be in the range [0.0 - 1.0].
Returns:

corresponding angles values in radians (vector of size 2).

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 (see Camera Indexes).
  • AngularPosition – Vector of size 2 containing the camera angle values in radians along the horizontal and vertical dimensions of the image.
Returns:

corresponding normalized position in the image [0.0 - 1.0] (vector of size 2).

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 (see Camera Indexes).
  • ImageSize – Vector of size 2 containing the normalized position along the horizontal and vertical dimensions of the image. The two values must be in the range [0.0 - 1.0].
Returns:

corresponding angles values in radians (vector of size 2).

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 (see Camera Indexes).
  • AngularSize – Vector of size 2 containing the camera angle values in radians along the horizontal and vertical dimensions of the image.
Returns:

corresponding normalized position in the image [0.0 - 1.0] (vector of size 2).

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 (see Camera Indexes).
  • AngularInfo – Vector of size 2 containing the camera angle values in radians along the horizontal and vertical dimensions of the image.
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 (see Camera Indexes).
  • AngularInfo – Vector of size 2 containing the camera angle values in radians along the horizontal and vertical dimensions of the image.
  • ResolutionIndex – image resolution
Returns:

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

Deprecated Methods

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

Deprecated since version 1.16.

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.
std::string ALVideoDeviceProxy::subscribe(const std::string& Name, const int& resolution, const int& colorSpace, const int& fps)

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

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:
  • Name – Name of the subscribing module.
  • resolution – Resolution requested. (see Supported resolutions)
  • colorSpace – Colorspace requested. (see Supported colorspaces)
  • 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)

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

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

Parameters:
  • Name – Name of the subscribing module.
int ALVideoDeviceProxy::getVIMResolution()

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

Gets the resolution of the video source before eventual conversion.

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

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

Gets the color space of the video source before eventual conversion.

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

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

Gets the internal frame rate of the video source.

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

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

Gets the resolution of a particular Vision Module

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

Supported resolutions or -1: can’t access video source

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

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

Gets the color space of a particular Vision Module.

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

Supported colorspaces -1: can’t access video source

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

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

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::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

bool ALVideoDeviceProxy::startFrameGrabber(const int& CameraIndex)

Deprecated since version 1.22: use ALVideoDeviceProxy::openCamera or ALVideoDeviceProxy::startCamera according to your need.

Opens and initializes the video source device if it was not already opened. Then starts the image acquisition.

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 (see Camera Indexes).
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::stopFrameGrabber(const int& CameraIndex)

Deprecated since version 1.22: use ALVideoDeviceProxy::stopCamera or ALVideoDeviceProxy::closeCamera according to your need.

Stops image acquisition, then releases and 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 (see Camera Indexes).
Returns:

true if success, false otherwise.

bool ALVideoDeviceProxy::isFrameGrabberOff(const int& CameraIndex)

Deprecated since version 1.22: use ALVideoDeviceProxy::isCameraOpen or ALVideoDeviceProxy::isCameraStarted according to your need.

Asks if the framegrabber is running or not.

Parameters:
  • CameraIndex – Index of the camera in the video system (see Camera Indexes).
Returns:

true if success, false otherwise.

int ALVideoDeviceProxy::getCameraModelID()

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

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

Returns:Camera model.
int ALVideoDeviceProxy::getParam(const int& Param)

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

Gets a parameter value of the currently default active camera.

Warning

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

Parameters:
Returns:

Parameter’s value.

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)

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

Sets the value of a specific parameter for the currently default active camera.

Parameters:
  • Param – Parameter’s reference (see 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)

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

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

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)

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

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.

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)

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

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.

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)

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

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)

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

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)

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

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]

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)

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

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]

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

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

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)

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

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

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

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

Allow image buffer pushing

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

true if success

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

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

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;

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)

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

return the resolution from sizes

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

Supported resolutions 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;
}
bool ALVideoDeviceProxy::startFrameGrabber()

Deprecated since version 1.14: use ALVideoDeviceProxy::openCamera instead.

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
bool ALVideoDeviceProxy::stopFrameGrabber()

Deprecated since version 1.14: use ALVideoDeviceProxy::closeCamera instead.

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

Deprecated since version 1.14: use ALVideoDeviceProxy::isCameraOpen instead.

Asks if the framegrabber is running or not.

Returns:true if off
float ALVideoDeviceProxy::getHorizontalAperture(const int& CameraIndex)

Deprecated since version 1.14: use ALVideoDeviceProxy::getHorizontalFOV instead.

Gets the camera horizontal field of view for the specified camera.

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

Horizontal field of view of the camera (in radian).

float ALVideoDeviceProxy::getVerticalAperture(const int& CameraIndex)

Deprecated since version 1.14: use ALVideoDeviceProxy::getVerticalFOV instead.

Gets the camera vertical field of view for the specified camera.

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

Vertical field of view of the camera (in radian).

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

Deprecated since version 1.20: use ALVideoRecorderProxy::startRecording instead.

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

Warning

Due to technical issues, do not use ARV format any longer.

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.

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

Deprecated since version 1.20: use ALVideoRecorderProxy::stopRecording instead.

Stops writing the video sequence.

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

true if success.

Cameras

Cameras specifiactions

nao NAO juju Pepper
Video camera 2D Cameras

Camera Indexes

nao NAO juju Pepper
Camera indexes Camera indexes

Camera model

nao NAO juju Pepper
Model Model

Camera parameters

nao NAO juju Pepper
Supported parameters Supported parameters

Supported colorspaces

nao NAO juju Pepper
Supported colorspaces Supported colorspaces

Supported resolutions

nao NAO juju Pepper
Supported resolutions Supported resolutions

Supported framerates

nao NAO juju Pepper
Supported framerates Supported framerates

Internal Types

Image

Image container is an array as follow:

  • [0]: width.
  • [1]: height.
  • [2]: number of layers.
  • [3]: ColorSpace.
  • [4]: time stamp from qi::Clock (seconds).
  • [5]: time stamp from qi::Clock (microseconds).
  • [6]: binary 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 image containers as follow:

  • [0] First Image, an array containing:
    • [0]: width.
    • [1]: height.
    • [2]: number of layers.
    • [3]: ColorSpace.
    • [4]: time stamp from qi::Clock (seconds).
    • [5]: time stamp from qi::Clock (microseconds).
    • [6]: binary 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).
  • [1] Second Image.
    • [0]: width.
    • [1]: height.
    • [2]: number of layers.
    • [3]: ColorSpace.
    • [4]: time stamp from qi::Clock (seconds).
    • [5]: time stamp from qi::Clock (microseconds).
    • [6]: binary 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).