35#ifdef ROS_DISTRO_IS_ROLLING
36#include <tf2_ros/transform_listener.hpp>
38#include <tf2_ros/transform_listener.h>
42#include <auterion_core_msgs/msg/camera_info.hpp>
43#include <auterion_core_msgs/msg/image8m.hpp>
46#include <opencv2/core/mat.hpp>
47#include <rclcpp/rclcpp.hpp>
48#include <sensor_msgs/msg/camera_info.hpp>
56using namespace std::chrono_literals;
59class CameraMonitorImpl;
90 template <
typename ImageT = auterion_core_msgs::msg::Image8m>
92 : width(image.width), height(image.height),
step(image.
step), timestamp(image.stamp) {
93 const int encoding_len =
94 strnlen(
reinterpret_cast<const char*
>(image.encoding.data()), image.encoding.size());
95 const std::string encoding_str(
reinterpret_cast<const char*
>(image.encoding.data()),
97 if (encoding_str ==
"mono8") {
99 }
else if (encoding_str ==
"mono16") {
101 }
else if (encoding_str ==
"uyvy") {
103 }
else if (encoding_str ==
"yuyv") {
105 }
else if (encoding_str ==
"i420") {
109 }
else if (encoding_str ==
"nv12") {
112 }
else if (encoding_str ==
"rgb8") {
113 encoding = Encoding::RGB8;
114 }
else if (encoding_str ==
"rgba8") {
116 }
else if (encoding_str ==
"bgr8") {
117 encoding = Encoding::BGR8;
118 }
else if (encoding_str ==
"bayer_bggr8") {
120 }
else if (encoding_str ==
"bayer_gbrg8") {
122 }
else if (encoding_str ==
"bayer_grbg8") {
124 }
else if (encoding_str ==
"bayer_rggb8") {
129 template <
typename ImageT = auterion_core_msgs::msg::Image8m>
130 void toImage(ImageT& image) {
132 image.height = height;
134 image.stamp = timestamp;
136 case Encoding::Unknown:
137 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"unknown",
138 image.encoding.size());
141 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"mono8",
142 image.encoding.size());
145 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"mono16",
146 image.encoding.size());
149 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"uyvy",
150 image.encoding.size());
153 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"yuyv",
154 image.encoding.size());
157 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"i420",
158 image.encoding.size());
161 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"nv12",
162 image.encoding.size());
165 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"rgb8",
166 image.encoding.size());
169 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bgr8",
170 image.encoding.size());
173 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"rgba8",
174 image.encoding.size());
177 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_bggr8",
178 image.encoding.size());
181 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_gbrg8",
182 image.encoding.size());
185 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_grbg8",
186 image.encoding.size());
189 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_rggb8",
190 image.encoding.size());
195 size_t planeOffset(
int plane)
const;
196 size_t planeSizeBytes(
int plane)
const;
197 size_t imageSizeBytes()
const;
202 Encoding encoding{Encoding::Unknown};
204 rclcpp::Time timestamp{};
207 float framerate{0.f};
209 sensor_msgs::msg::CameraInfo camera_info{};
220 Image(
ImageHeader header, uint8_t* data) : _header(std::move(header)), _data(data) {}
222 const ImageHeader& header()
const {
return _header; }
224 uint8_t* data() {
return _data; }
225 const uint8_t* data()
const {
return _data; }
227 int width()
const {
return _header.width; }
228 int height()
const {
return _header.height; }
238 uint8_t* _data{
nullptr};
251 std::function<
void()> release_function)
252 : _header(std::move(header)),
254 _buffer_size(buffer_size),
255 _release_function(std::move(release_function)) {}
266 : _header(std::move(other._header)),
268 _buffer_size(other._buffer_size),
269 _release_function(std::move(other._release_function)),
270 _was_released(other._was_released) {
272 other._buffer_size = 0;
273 other._release_function =
nullptr;
274 other._was_released =
true;
279 if (
this != &other) {
281 _header = std::move(other._header);
283 _buffer_size = other._buffer_size;
284 _release_function = std::move(other._release_function);
285 _was_released = other._was_released;
287 other._buffer_size = 0;
288 other._release_function =
nullptr;
289 other._was_released =
true;
294 const ImageHeader& header()
const {
return _header; }
296 int fd()
const {
return _fd; }
298 uint64_t bufferSize()
const {
return _buffer_size; }
304 if (_release_function) {
306 _release_function =
nullptr;
309 _was_released =
true;
312 bool wasReleased()
const {
return _was_released; }
317 uint64_t _buffer_size{0};
325 std::function<void()> _release_function{
nullptr};
327 bool _was_released{
false};
335 enum class SensorType {
343 enum class MountOrientation {
353 enum class MountOrientationDetail {
360 enum class PrimaryPurpose {
370 Eigen::Quaterniond rotation{-0.5, 0.5, -0.5, 0.5};
371 Eigen::Vector3d translation{0.0, 0.0, 0.0};
375 explicit CameraDescriptor(
const auterion_core_msgs::msg::CameraInfo& camera_info);
377 operator auterion_core_msgs::msg::CameraInfo()
const;
379 std::string device_driver;
380 std::string device_identifier;
382 std::string unique_hash;
383 std::string unique_name;
385 std::string camera_model;
387 SensorType sensor_type{SensorType::Unknown};
388 MountOrientation mount_orientation{MountOrientation::Unknown};
389 MountOrientationDetail mount_orientation_detail{MountOrientationDetail::Unknown};
390 PrimaryPurpose primary_purpose{PrimaryPurpose::Unknown};
391 ExtrinsicCalibration extrinsic_calibration;
404 const NotificationCallback& on_camera_removed =
nullptr);
409 std::shared_ptr<CameraMonitorImpl> _impl;
428 "waitForCamera with 'camera_descriptor' not used anymore. This will be removed in some "
429 "later release.")]]
static Camera
431 std::optional<auterion::CameraDescriptor> camera_descriptor = std::nullopt);
433 static std::optional<Camera> open(
SDK& sdk,
const std::string& unique_name,
434 const std::chrono::seconds& timeout = 30s);
435 static std::optional<Camera> open(
437 const std::chrono::seconds& timeout = 30s);
438 static std::optional<Camera> openFirst(
SDK& sdk,
const std::chrono::seconds& timeout = 30s);
440 using ImageCallback = std::function<void(
const Image& image)>;
441 using ImageFDCallback = std::function<void(
const std::shared_ptr<ImageFD>& image_fd)>;
457 void subscribeImageFD(
const ImageFDCallback& callback);
460 "subscribeCameraInfo() is deprecated and will be removed in a future release. The "
461 "CameraInfo is instead included in the image header obtained with subscribeImage(), and "
462 "can also be queried with getCameraInfo().")]]
void
464 std::function<
void(
const sensor_msgs::msg::CameraInfo::SharedPtr)> callback);
505 bool getPoseBodyCamera(Eigen::Quaterniond& q_body_camera, Eigen::Vector3d& t_body_camera)
const;
526 const tf2::TimePoint& time = tf2::TimePointZero)
const;
558 tf2::TimePoint& time_start, tf2::TimePoint& time_end);
571 std::shared_ptr<CameraImpl> _impl;
Monitor for new or removed cameras. This will also list all existing cameras upon creating the object...
Definition camera.hpp:399
Camera client to subscribe to a camera image stream.
Definition camera.hpp:416
bool cameraInfoValid() const
Determine whether a camera info message contains valid data.
bool getCameraInfo(sensor_msgs::msg::CameraInfo &camera_info) const
Get the camera information data for the camera.
bool getPoseBodyCamera(Eigen::Quaterniond &q_body_camera, Eigen::Vector3d &t_body_camera) const
Get the pose of the camera with respect to the body frame.
void subscribeImage(const ImageCallback &callback)
Eigen::Vector3d unprojectImagePoint(const cv::Point &image_point) const
Determine the (relative) camera-frame 3D position of a point in an image.
bool getDeltaRotationWorldCamera(Eigen::Quaterniond &q_delta_world_camera, tf2::TimePoint &time_start, tf2::TimePoint &time_end)
Calculates how much the camera has rotated between two points in time based only on gyro data.
std::optional< cv::Size > getLastImageSize() const
Returns the size of the last received image, if available.
static Camera waitForCamera(SDK &sdk, const std::function< bool(const CameraDescriptor &)> &find_callback)
bool getPoseWorldCamera(Eigen::Quaterniond &q_enu_camera, Eigen::Vector3d &t_enu_camera, const tf2::TimePoint &time=tf2::TimePointZero) const
Get the pose of the camera with respect to the ENU world frame.
Definition camera.hpp:248
Contains image data with a specific encoding.
Definition camera.hpp:218
cv::Mat asOpenCVMat(int plane=-1) const
SDK execution class. All callbacks are called on the same thread.
Definition auterion.hpp:97
Definition camera.hpp:369
Struct describing a camera configuration.
Definition camera.hpp:334