Camera API
Auterion SDK provides an interface for enumerating and subscribing to cameras and images.
In the simplest case (useful for testing), we can open the first found camera, and register a callback for image updates:
std::optional<auterion::Camera> camera = auterion::Camera::openFirst(sdk);
if (camera) {
printf("Got camera: %s, model=%s\n", camera->descriptor().unique_name.c_str(),
camera->descriptor().camera_model.c_str());
camera->subscribeImage([](const auterion::Image& image) {
// The image data is available as image.data(),
// encoded as image.header().encoding
printf("Got image: size=%dx%d\n", image.width(), image.height());
});
} else {
printf("Timeout, no camera found\n");
}
As the set of available cameras depends on the system, each camera provides a descriptor, which can be used to select a camera based on its properties, such as the model name, mount orientation or purpose.
For example to select the camera used for surveys:
std::optional<auterion::Camera> camera = auterion::Camera::open(
sdk,
[](const auterion::CameraDescriptor& descriptor) {
// The camera will be selected for the first descriptor that returns true here
return descriptor.primary_purpose ==
auterion::CameraDescriptor::PrimaryPurpose::Survey;
});
if (camera) {
// ...
}
Image Data
The raw image data can be accessed from the callback via image.data()
.
The image can be converted to an OpenCV structure like this:
const cv::Mat cv_mat = image.asOpenCVMat();
If you want to use the image outside of the callback, or make modifications, it is required to make a copy of the image data.
CameraMonitor
In addition, there's also a CameraMonitor
class that can be used to get notified when cameras are attached or removed from the system:
auto monitor = auterion::CameraMonitor(
sdk,
[](const auterion::CameraDescriptor& descriptor) {
printf("Camera found: %s\n", descriptor.camera_model.c_str());
},
[](const auterion::CameraDescriptor& descriptor) {
printf("Camera removed: %s\n", descriptor.camera_model.c_str());
});
Last updated