Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
|
Building block for a camera driver. More...
#include <auterion_sdk/camera/camera_provider.hpp>
Public Member Functions | |
CameraProvider (SDK &sdk, const std::string &device_driver, const std::string &device_identifier, const CameraDescriptor &camera_descriptor) | |
bool | configureImage (int width, int height, ImageHeader::Encoding encoding, int step=0) |
uint8_t * | getImageBuffer (int plane=0) |
void | publishImageBuffer (const rclcpp::Time ×tamp) |
bool | hasImageSubscribers () const |
void | publishCameraInfo (const sensor_msgs::msg::CameraInfo &info) const |
Building block for a camera driver.
A camera driver can use this class to register a camera and publish images. A client can then use Camera
to enumerate and subscribe to images.
auterion::CameraProvider::CameraProvider | ( | SDK & | sdk, |
const std::string & | device_driver, | ||
const std::string & | device_identifier, | ||
const CameraDescriptor & | camera_descriptor | ||
) |
Create a new camera provider. The {device_driver, device_identifier} pair is expected to be unique in the whole system.
sdk | |
device_driver | Name of the driver, e.g. "video4linux", must not include ':', ',' or '/' |
device_identifier | e.g. "/dev/v4l/by-path/pci-0000:00:14.0-usb-0:8:1.0-video-index0" |
camera_descriptor | Describes camera properties. As much information as available should be provided. unique_name will be set internally. |
bool auterion::CameraProvider::configureImage | ( | int | width, |
int | height, | ||
ImageHeader::Encoding | encoding, | ||
int | step = 0 |
||
) |
Configure the image. Call this before the first call to getImageBuffer(). This can also be called later on, e.g. when the image size changes.
width | Image width in pixels |
height | Image height in pixels |
encoding | Image encoding |
step | Full row length in bytes (for the first plane). The value should include the padding bytes at the end of each row, if any. If the parameter is set to 0, no padding is assumed |
uint8_t* auterion::CameraProvider::getImageBuffer | ( | int | plane = 0 | ) |
Get an unused image buffer. The steps for publishing an image are:
plane | Image plane if image has multiple planes, e.g. for I420: 0=Y, 1=U, 2=V |
bool auterion::CameraProvider::hasImageSubscribers | ( | ) | const |
Check if there are any image subscribers. It can be used to bypass image copy and publication in case there are not subscribers. configureImage() must still be called in any case.
void auterion::CameraProvider::publishCameraInfo | ( | const sensor_msgs::msg::CameraInfo & | info | ) | const |
Publish a new camera info message. Thread-safe: yes
void auterion::CameraProvider::publishImageBuffer | ( | const rclcpp::Time & | timestamp | ) |
Publish the image buffer that was previously returned in getImageBuffer().
timestamp | image capture timestamp |