NAOqi Vision - Overview | API | Tutorial | ALVideoDevice - Advanced
See also
Namespace : AL
#include <alproxies/alvideodeviceproxy.h>
As any module, this module inherits methods from ALModule API. It also has the following specific methods:
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).
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: |
|
---|---|
Returns: | String handle under which the module is known from ALVideoDevice. |
Warning
The same Name could be used only six time.
Note
Unregisters a module from ALVideoDevice.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
#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;
}
Gets a list containing all the handle name of the subscribers.
Returns: | Array of string containing the subscriber names. |
---|
Gets list of available camera indexes.
Returns: | Array of camera index (see Camera Indexes). |
---|
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. |
---|
Gets the camera model of the specified camera.
Parameters: |
|
---|---|
Returns: |
Gets the name of the specified camera.
Parameters: |
|
---|---|
Returns: | name of the camera (sensor name used by motion). |
Gets the index of the current default active camera.
Returns: | Camera Indexes. |
---|
#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;
}
Sets the current default active camera for the system.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Gets the internal frame rate of the video source.
Parameters: |
|
---|---|
Returns: | video source framerate. -1: can’t access video source. |
Gets the resolution of the video source before eventual conversion.
Parameters: |
|
---|---|
Returns: | Supported resolutions or -1: can’t access video source. |
Get the color space of the video source before eventual conversion.
Parameters: |
|
---|---|
Returns: | Supported colorspaces or -1: can’t access video source. |
Gets the camera horizontal field of view for the specified camera.
Parameters: |
|
---|---|
Returns: | Horizontal field of view of the camera (in radian). |
Gets the camera vertical field of view for the specified camera.
Parameters: |
|
---|---|
Returns: | Vertical field of view of the camera (in radian). |
Gets camera internal parameter.
Parameters: |
|
---|---|
Returns: | Value of the camera parameter. |
Gets the range of a camera’s parameter.
Parameters: |
|
---|---|
Returns: | An ALValue containing the minimum and maximum value for the requested parameter. |
Modifies camera internal parameter.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Resets camera internal parameter to its default value.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Resets all camera internal parameters to their default value.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Opens and initializes the video source device.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Closes the video source device, releasing resources.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Detects if the video device is open (i.e. locked).
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Starts the video capture of the specified video device.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Stops the video capture of the specified video device.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Detects if the video device is running (i.e. capture images).
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Gets the current active camera for the specified module.
Parameters: |
|
---|---|
Returns: | Camera Indexes or -1: can’t access video source. |
Sets the current active camera for the specified module.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
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: |
|
---|---|
Returns: | module framerate or -1: can’t access video source. |
Changes the framerate requested to the video source by the subscribed module.
Parameters: |
|
---|
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. |
---|
Gets the current resolution requested for the specified module.
Parameters: |
|
---|---|
Returns: |
Sets the size of the output image for the specified module.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Gets the current color space requested for the specified module.
Parameters: |
|
---|---|
Returns: | Supported colorspaces or -1: can’t access video source. |
Sets the current color space requested for the specified module.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Gets a camera’s parameter from the module current active camera. This method will probe for value of the current active camera of the module.
Parameters: |
|
---|---|
Returns: | Parameter’s value. |
Gets the range of a camera’s parameter from the module current active camera.
Parameters: |
|
---|---|
Returns: | An ALValue containing the minimum and maximum of the requested parameter. |
Sets the value of a specific parameter for the module current active camera.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Sets a camera’s parameter to its default value.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Resets all camera internal parameters to their default value.
Parameters: |
|
---|---|
Returns: | true if successful, false otherwise. |
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
Parameters: |
|
---|---|
Returns: | Pointer to the locked AL::ALImage buffer, NULL if error. |
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
Parameters: |
|
---|---|
Returns: | Container of image. |
Release image buffer locked by getDirectRawImageLocal(). If the module has no locked image buffer, does nothing.
Parameters: |
|
---|---|
Returns: | true if success |
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
Parameters: |
|
---|---|
Returns: | Pointer to the locked image buffer, NULL if error (e.g. if the previous image was not released). |
#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;
}
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: |
|
---|---|
Returns: | Container of image. |
#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;
}
Release image buffer locked by getImageLocal(). If module had no locked image buffer, does nothing.
Parameters: |
|
---|---|
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).
#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;
}
Gets current active cameras for the specified module.
Parameters: |
|
---|---|
Returns: | Array of camera indexes (see Camera Indexes) or -1: can’t access video source. |
Sets the current active cameras for the specified module.
Parameters: |
|
---|---|
Returns: | Array of booleans with true if success. |
Gets the current resolutions requested for the specified module.
Parameters: |
|
---|---|
Returns: | Array of resolutions (see Supported resolutions). |
Sets the size of the output image for the specified module.
Parameters: |
|
---|---|
Returns: | Array of booleans with true if success. |
Gets the current color spaces requested for the specified module.
Parameters: |
|
---|---|
Returns: | Array of color spaces (see Supported colorspaces). |
Sets the current color spaces requested for the specified module.
Parameters: |
|
---|---|
Returns: | Array of booleans with true if success |
Gets a camera’s parameter from the module current active cameras. This method will probe for value of the current active camera of the module.
Parameters: |
|
---|---|
Returns: | Parameter’s values. |
Sets the values of a specific parameter for the module current active cameras.
Parameters: |
|
---|---|
Returns: | Array of booleans with true if success. |
Sets a camera’s parameter to its default value.
Parameters: |
|
---|---|
Returns: | Array of booleans with true if success. |
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
Parameters: |
|
---|---|
Returns: | Array of pointers to the locked AL::ALImage buffer, NULL if error. |
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: |
|
---|---|
Returns: | Container of images. |
Release image buffer locked by getDirectRawImagesLocal(). If the module has no locked image buffer, does nothing.
Parameters: |
|
---|---|
Returns: | true if success |
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
Parameters: |
|
---|---|
Returns: | Array of pointers to locked AL::ALImage buffers, NULL if error (e.g. if the previous images was not released). |
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: |
|
---|---|
Returns: | Container of images. |
Release image buffers locked by getImagesLocal(). If module had no locked image buffers, does nothing.
Parameters: |
|
---|---|
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).
Loads Image into kernel circular buffer. Simulates acquisition of a new image by the virtual camera.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Warning
This method only works in simulation.
Called by the simulator to know expected image parameters
Parameters: |
|
---|---|
Returns: | ALValue of expected parameters: [int height, int width, int framerate] |
Warning
This method only works in simulation.
Returns position as angles relative to camera axis given a normalized position in the image.
Parameters: |
|
---|---|
Returns: | corresponding angles values in radians (vector of size 2). |
Returns a normalized position in the image from a position expressed with camera angles in radians.
Parameters: |
|
---|---|
Returns: | corresponding normalized position in the image [0.0 - 1.0] (vector of size 2). |
From a normalized size in the image, returns size expressed as angles in radian relative to camera axis.
Parameters: |
|
---|---|
Returns: | corresponding angles values in radians (vector of size 2). |
Returns a normalized size from a size expressed with camera angles in radians.
Parameters: |
|
---|---|
Returns: | corresponding normalized position in the image [0.0 - 1.0] (vector of size 2). |
Returns [X, Y, width, height] normalized info in the image from these info expressed as angles in radians (as returned by vision extractors).
Parameters: |
|
---|---|
Returns: | corresponding normalized position and size info: [X, Y, width, height]. |
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: |
|
---|---|
Returns: | corresponding pixels position and size info: [X, Y, width, height]. |
Deprecated since version 1.16.
Callback when client is disconnected
Parameters: |
|
---|
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: |
|
---|---|
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).
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: |
|
---|
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 |
---|
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 |
---|
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 |
---|
Deprecated since version 1.14: use ALVideoDeviceProxy::getResolution() instead.
Gets the resolution of a particular Vision Module
Parameters: |
|
---|---|
Returns: | Supported resolutions or -1: can’t access video source |
Deprecated since version 1.14: use ALVideoDeviceProxy::getColorSpace() instead.
Gets the color space of a particular Vision Module.
Parameters: |
|
---|---|
Returns: | Supported colorspaces -1: can’t access video source |
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: |
|
---|---|
Returns: | The Vision Module framerate, or -1 if we can’t access video source |
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: |
|
---|---|
Returns: | true if success, false otherwise. |
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: |
|
---|---|
Returns: | true if success, false otherwise. |
Deprecated since version 1.22: use ALVideoDeviceProxy::isCameraOpen() or ALVideoDeviceProxy::isCameraStarted() according to your need.
Asks if the framegrabber is running or not.
Parameters: |
|
---|---|
Returns: | true if success, false otherwise. |
Deprecated since version 1.14: use ALVideoDeviceProxy::getCameraModel() instead.
Gets the camera model index of the current default active camera.
Returns: | Camera model. |
---|
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. |
#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;
}
Deprecated since version 1.14: use ALVideoDeviceProxy::setCameraParameter() instead.
Sets the value of a specific parameter for the currently default active camera.
Parameters: |
|
---|
#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;
}
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;
}
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: |
|
---|---|
Returns: | corresponding angles values in radians. |
#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;
}
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: |
|
---|---|
Returns: | corresponding angles values in radians. |
#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;
}
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: |
|
---|---|
Returns: | corresponding normalized position and size info: [X, Y, width, height]. |
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: |
|
---|---|
Returns: | corresponding pixels position and size info: [X, Y, width, height]. |
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: |
|
---|---|
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;
}
Deprecated since version 1.14: use ALVideoDeviceProxy::getImageSizeFromAngularSize() instead.
Returns a normalized size from a size expressed with camera angles in radians.
Parameters: |
|
---|---|
Returns: | corresponding normalized position in the image [0.0 - 1.0] |
#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;
}
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] |
---|
Deprecated since version 1.14: use ALVideoDeviceProxy::putImage() instead.
Set parameters for the images that the simulator will provide.
Parameters: |
|
---|---|
Returns: | true if success |
Deprecated since version 1.14: use ALVideoDeviceProxy::putImage() instead.
Allow image buffer pushing
Parameters: |
|
---|---|
Returns: | true if success |
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: |
|
---|---|
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;
}
Deprecated since version 1.14: use AL::getResolutionFromSize instead. For further details, see: libalvision API reference.
return the resolution from sizes
Parameters: |
|
---|---|
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;
}
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 |
---|
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 |
---|
Deprecated since version 1.14: use ALVideoDeviceProxy::isCameraOpen() instead.
Asks if the framegrabber is running or not.
Returns: | true if off |
---|
Deprecated since version 1.14: use ALVideoDeviceProxy::getHorizontalFOV() instead.
Gets the camera horizontal field of view for the specified camera.
Parameters: |
|
---|---|
Returns: | Horizontal field of view of the camera (in radian). |
Deprecated since version 1.14: use ALVideoDeviceProxy::getVerticalFOV() instead.
Gets the camera vertical field of view for the specified camera.
Parameters: |
|
---|---|
Returns: | Vertical field of view of the camera (in radian). |
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: |
|
---|---|
Returns: | true if success. |
Deprecated since version 1.20: use ALVideoRecorderProxy::stopRecording() instead.
Stops writing the video sequence.
Parameters: |
|
---|---|
Returns: | true if success. |
NAO |
NAO - Video camera |
NAO |
Camera indexes |
NAO |
Supported parameters |
NAO |
Supported colorspaces |
NAO |
Supported resolutions |
NAO |
Supported framerates |
Image
Image container is an array as follow:
Images
Images container is an array of image containers as follow: