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.
- param –
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
- param –
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; }