35 #include <rclcpp/rclcpp.hpp>
44 class CameraProviderImpl;
64 CameraProvider(
SDK& sdk,
const std::string& device_driver,
const std::string& device_identifier,
111 std::shared_ptr<CameraProviderImpl> _impl;
Building block for a camera driver.
Definition: camera_provider.hpp:53
uint8_t * getImageBuffer(int plane=0)
bool hasImageSubscribers() const
bool configureImage(int width, int height, ImageHeader::Encoding encoding, int step=0)
void publishImageBuffer(const rclcpp::Time ×tamp)
void publishCameraInfo(const sensor_msgs::msg::CameraInfo &info) const
CameraProvider(SDK &sdk, const std::string &device_driver, const std::string &device_identifier, const CameraDescriptor &camera_descriptor)
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:45
Struct describing a camera configuration.
Definition: camera.hpp:229