35#include <rclcpp/rclcpp.hpp>
44class CameraProviderImpl;
64 CameraProvider(
SDK& sdk,
const std::string& device_driver,
const std::string& device_identifier,
143 void updateExtrinsics(
const Eigen::Vector3d& translation,
const Eigen::Quaterniond& rotation,
144 const rclcpp::Time& timestamp);
154 void updateExtrinsics(
const Eigen::Vector3d& translation,
const Eigen::Quaterniond& rotation);
157 std::shared_ptr<CameraProviderImpl> _impl;
Building block for a camera driver.
Definition camera_provider.hpp:53
bool hasCameraInfoSubscribers() const
bool hasImageSubscribers() const
void updateExtrinsics(const Eigen::Vector3d &translation, const Eigen::Quaterniond &rotation, const rclcpp::Time ×tamp)
Update the camera extrinsics.
bool configureImage(int width, int height, ImageHeader::Encoding encoding, int step=0)
uint8_t * getImageBuffer(int plane=0)
std::string getUniqueCameraName() const
void publishImageBuffer(const rclcpp::Time ×tamp)
void updateExtrinsics(const Eigen::Vector3d &translation, const Eigen::Quaterniond &rotation)
Update the camera extrinsics using the current time.
void publishCameraInfo(const sensor_msgs::msg::CameraInfo &info) const
std::string getUniqueCameraHash() 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:97
Struct describing a camera configuration.
Definition camera.hpp:334