35 #include <rclcpp/rclcpp.hpp>
44 class CameraProviderImpl;
64 CameraProvider(
SDK& sdk,
const std::string& device_driver,
const std::string& device_identifier,
126 void updateExtrinsics(
const Eigen::Vector3d& translation,
const Eigen::Quaterniond& rotation,
127 const rclcpp::Time& timestamp);
137 void updateExtrinsics(
const Eigen::Vector3d& translation,
const Eigen::Quaterniond& rotation);
140 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
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)
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
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:47
Struct describing a camera configuration.
Definition: camera.hpp:229