Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
Loading...
Searching...
No Matches
camera.hpp
1/****************************************************************************
2 *
3 * Copyright 2023-2026 Auterion AG. All rights reserved.
4 *
5 * Redistribution and use in source and binary forms, with or without
6 * modification, are permitted provided that the following conditions are met:
7 *
8 * 1. Redistributions of source code must retain the above copyright notice, this
9 * list of conditions and the following disclaimer.
10 *
11 * 2. Redistributions in binary form must reproduce the above copyright notice,
12 * this list of conditions and the following disclaimer in the documentation
13 * and/or other materials provided with the distribution.
14 *
15 * 3. Neither the name of the copyright holder nor the names of its contributors
16 * may be used to endorse or promote products derived from this software without
17 * specific prior written permission.
18 *
19 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29 * POSSIBILITY OF SUCH DAMAGE.
30 *
31 ****************************************************************************/
32
33#pragma once
34
35#ifdef ROS_DISTRO_IS_ROLLING
36#include <tf2_ros/transform_listener.hpp>
37#else
38#include <tf2_ros/transform_listener.h>
39#endif
40
41#include <Eigen/Eigen>
42#include <auterion_core_msgs/msg/camera_info.hpp>
43#include <auterion_core_msgs/msg/image8m.hpp>
44#include <chrono>
45#include <functional>
46#include <opencv2/core/mat.hpp>
47#include <rclcpp/rclcpp.hpp>
48#include <sensor_msgs/msg/camera_info.hpp>
49#include <string>
50#include <utility>
51
52namespace auterion {
56using namespace std::chrono_literals;
57
58class SDK;
59class CameraMonitorImpl;
60class CameraImpl;
61
67 ImageHeader() = default;
68
70 enum class Encoding {
71 Unknown,
72 Y800,
73 Y16,
74 UYVY,
75 YUY2,
76 I420,
77 NV12,
78 RGB8,
79 BGR8,
81 BA81,
82 GBRG,
83 GRBG,
84 RGGB,
85 RGBA
86 };
87
88 ImageHeader(int width_, int height_, Encoding encoding_, int step_ = 0);
89
90 template <typename ImageT = auterion_core_msgs::msg::Image8m>
91 explicit ImageHeader(const ImageT& image)
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()),
96 encoding_len);
97 if (encoding_str == "mono8") {
98 encoding = Encoding::Y800;
99 } else if (encoding_str == "mono16") {
100 encoding = Encoding::Y16;
101 } else if (encoding_str == "uyvy") {
102 encoding = Encoding::UYVY;
103 } else if (encoding_str == "yuyv") {
104 encoding = Encoding::YUY2;
105 } else if (encoding_str == "i420") {
106 // (This does not exist in ROS:
107 // https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/include/sensor_msgs/image_encodings.hpp)
108 encoding = Encoding::I420;
109 } else if (encoding_str == "nv12") {
110 // Does not exist in ROS 2
111 encoding = Encoding::NV12;
112 } else if (encoding_str == "rgb8") {
113 encoding = Encoding::RGB8;
114 } else if (encoding_str == "rgba8") {
115 encoding = Encoding::RGBA;
116 } else if (encoding_str == "bgr8") {
117 encoding = Encoding::BGR8;
118 } else if (encoding_str == "bayer_bggr8") {
119 encoding = Encoding::BA81;
120 } else if (encoding_str == "bayer_gbrg8") {
121 encoding = Encoding::GBRG;
122 } else if (encoding_str == "bayer_grbg8") {
123 encoding = Encoding::GRBG;
124 } else if (encoding_str == "bayer_rggb8") {
125 encoding = Encoding::RGGB;
126 }
127 }
128
129 template <typename ImageT = auterion_core_msgs::msg::Image8m>
130 void toImage(ImageT& image) {
131 image.width = width;
132 image.height = height;
133 image.step = step;
134 image.stamp = timestamp;
135 switch (encoding) {
136 case Encoding::Unknown:
137 strncpy(reinterpret_cast<char*>(image.encoding.data()), "unknown",
138 image.encoding.size());
139 break;
140 case Encoding::Y800:
141 strncpy(reinterpret_cast<char*>(image.encoding.data()), "mono8",
142 image.encoding.size());
143 break;
144 case Encoding::Y16:
145 strncpy(reinterpret_cast<char*>(image.encoding.data()), "mono16",
146 image.encoding.size());
147 break;
148 case Encoding::UYVY:
149 strncpy(reinterpret_cast<char*>(image.encoding.data()), "uyvy",
150 image.encoding.size());
151 break;
152 case Encoding::YUY2:
153 strncpy(reinterpret_cast<char*>(image.encoding.data()), "yuyv",
154 image.encoding.size());
155 break;
156 case Encoding::I420:
157 strncpy(reinterpret_cast<char*>(image.encoding.data()), "i420",
158 image.encoding.size());
159 break;
160 case Encoding::NV12:
161 strncpy(reinterpret_cast<char*>(image.encoding.data()), "nv12",
162 image.encoding.size());
163 break;
164 case Encoding::RGB8:
165 strncpy(reinterpret_cast<char*>(image.encoding.data()), "rgb8",
166 image.encoding.size());
167 break;
168 case Encoding::BGR8:
169 strncpy(reinterpret_cast<char*>(image.encoding.data()), "bgr8",
170 image.encoding.size());
171 break;
172 case Encoding::RGBA:
173 strncpy(reinterpret_cast<char*>(image.encoding.data()), "rgba8",
174 image.encoding.size());
175 break;
176 case Encoding::BA81:
177 strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_bggr8",
178 image.encoding.size());
179 break;
180 case Encoding::GBRG:
181 strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_gbrg8",
182 image.encoding.size());
183 break;
184 case Encoding::GRBG:
185 strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_grbg8",
186 image.encoding.size());
187 break;
188 case Encoding::RGGB:
189 strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_rggb8",
190 image.encoding.size());
191 break;
192 }
193 }
194
195 size_t planeOffset(int plane) const;
196 size_t planeSizeBytes(int plane) const;
197 size_t imageSizeBytes() const;
198
199 int width{};
200 int height{};
201 int step{};
202 Encoding encoding{Encoding::Unknown};
203
204 rclcpp::Time timestamp{};
205 std::optional<uint64_t> monotonic_timestamp_us{std::nullopt};
206
207 float framerate{0.f};
208
209 sensor_msgs::msg::CameraInfo camera_info{};
210};
211
212std::ostream& operator<<(std::ostream& os, const ImageHeader::Encoding& encoding);
213
218class Image {
219 public:
220 Image(ImageHeader header, uint8_t* data) : _header(std::move(header)), _data(data) {}
221
222 const ImageHeader& header() const { return _header; }
223
224 uint8_t* data() { return _data; }
225 const uint8_t* data() const { return _data; }
226
227 int width() const { return _header.width; }
228 int height() const { return _header.height; }
229
234 cv::Mat asOpenCVMat(int plane = -1) const;
235
236 private:
237 ImageHeader _header{};
238 uint8_t* _data{nullptr};
239};
240
248class ImageFD {
249 public:
250 ImageFD(ImageHeader header, int fd, uint64_t buffer_size,
251 std::function<void()> release_function)
252 : _header(std::move(header)),
253 _fd(fd),
254 _buffer_size(buffer_size),
255 _release_function(std::move(release_function)) {}
256
257 ~ImageFD() { release(); }
258
259 // Delete copy operations
260 // Copying an ImageFD is not allowed since it contains an FD that should be uniquely owned.
261 ImageFD(const ImageFD&) = delete;
262 ImageFD& operator=(const ImageFD&) = delete;
263
264 // Move constructor
265 ImageFD(ImageFD&& other) noexcept
266 : _header(std::move(other._header)),
267 _fd(other._fd),
268 _buffer_size(other._buffer_size),
269 _release_function(std::move(other._release_function)),
270 _was_released(other._was_released) {
271 other._fd = -1;
272 other._buffer_size = 0;
273 other._release_function = nullptr;
274 other._was_released = true;
275 }
276
277 // Move assignment operator
278 ImageFD& operator=(ImageFD&& other) noexcept {
279 if (this != &other) {
280 release();
281 _header = std::move(other._header);
282 _fd = other._fd;
283 _buffer_size = other._buffer_size;
284 _release_function = std::move(other._release_function);
285 _was_released = other._was_released;
286 other._fd = -1;
287 other._buffer_size = 0;
288 other._release_function = nullptr;
289 other._was_released = true;
290 }
291 return *this;
292 }
293
294 const ImageHeader& header() const { return _header; }
295
296 int fd() const { return _fd; }
297
298 uint64_t bufferSize() const { return _buffer_size; }
299
300 /*
301 * Release the FD, signalling that the buffer is no longer in use.
302 */
303 void release() {
304 if (_release_function) {
305 _release_function();
306 _release_function = nullptr;
307 }
308 _fd = -1;
309 _was_released = true;
310 }
311
312 bool wasReleased() const { return _was_released; }
313
314 private:
315 ImageHeader _header{};
316 int _fd{-1};
317 uint64_t _buffer_size{0};
318
325 std::function<void()> _release_function{nullptr};
326
327 bool _was_released{false};
328};
329
335 enum class SensorType {
336 Unknown = 0,
337 Monochrome = 1,
338 RGB = 2,
339 Depth = 3,
340 RGBD = 4,
341 IR = 5,
342 };
343 enum class MountOrientation {
344 Unknown = 0,
345 Dynamic = 1,
346 Forward = 2,
347 Backward = 3,
348 Upward = 4,
349 Downward = 5,
350 Leftward = 6,
351 Rightward = 7,
352 };
353 enum class MountOrientationDetail {
354 Unknown = 0,
355 Left = 1,
356 Right = 2,
357 Upper = 3,
358 Lower = 4,
359 };
360 enum class PrimaryPurpose {
361 Unknown = 0,
362 Generic = 1,
363 OpticalFlow = 2,
364 VIO = 3,
365 FPV = 4,
366 Survey = 5,
367 Tracking = 6,
368 };
370 Eigen::Quaterniond rotation{-0.5, 0.5, -0.5, 0.5}; // {q, x, y, z} default front facing
371 Eigen::Vector3d translation{0.0, 0.0, 0.0};
372 };
373
374 CameraDescriptor() = default;
375 explicit CameraDescriptor(const auterion_core_msgs::msg::CameraInfo& camera_info);
376
377 operator auterion_core_msgs::msg::CameraInfo() const;
378
379 std::string device_driver;
380 std::string device_identifier;
381
382 std::string unique_hash;
383 std::string unique_name;
384
385 std::string camera_model;
386
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;
392};
393
400 public:
401 using NotificationCallback = std::function<void(const CameraDescriptor&)>;
402
403 CameraMonitor(SDK& sdk, const NotificationCallback& on_camera_added,
404 const NotificationCallback& on_camera_removed = nullptr);
405
406 ~CameraMonitor() = default;
407
408 private:
409 std::shared_ptr<CameraMonitorImpl> _impl;
410};
411
416class Camera {
417 public:
418 Camera(SDK& sdk, const CameraDescriptor& camera_descriptor);
419 ~Camera() = default;
420
425 const std::function<bool(const CameraDescriptor&)>& find_callback);
426
427 [[deprecated(
428 "waitForCamera with 'camera_descriptor' not used anymore. This will be removed in some "
429 "later release.")]] static Camera
430 waitForCamera(SDK& sdk,
431 std::optional<auterion::CameraDescriptor> camera_descriptor = std::nullopt);
432
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(
436 SDK& sdk, const std::function<bool(const CameraDescriptor&)>& find_callback,
437 const std::chrono::seconds& timeout = 30s);
438 static std::optional<Camera> openFirst(SDK& sdk, const std::chrono::seconds& timeout = 30s);
439
440 using ImageCallback = std::function<void(const Image& image)>;
441 using ImageFDCallback = std::function<void(const std::shared_ptr<ImageFD>& image_fd)>;
442
448 void subscribeImage(const ImageCallback& callback);
449
457 void subscribeImageFD(const ImageFDCallback& callback);
458
459 [[deprecated(
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
463 subscribeCameraInfo(
464 std::function<void(const sensor_msgs::msg::CameraInfo::SharedPtr)> callback);
465
471 bool cameraInfoValid() const;
472
481 std::optional<cv::Size> getLastImageSize() const;
482
489 Eigen::Vector3d unprojectImagePoint(const cv::Point& image_point) const;
490
505 bool getPoseBodyCamera(Eigen::Quaterniond& q_body_camera, Eigen::Vector3d& t_body_camera) const;
506
525 bool getPoseWorldCamera(Eigen::Quaterniond& q_enu_camera, Eigen::Vector3d& t_enu_camera,
526 const tf2::TimePoint& time = tf2::TimePointZero) const;
527
557 bool getDeltaRotationWorldCamera(Eigen::Quaterniond& q_delta_world_camera,
558 tf2::TimePoint& time_start, tf2::TimePoint& time_end);
559
566 bool getCameraInfo(sensor_msgs::msg::CameraInfo& camera_info) const;
567
568 const CameraDescriptor& descriptor() const;
569
570 private:
571 std::shared_ptr<CameraImpl> _impl;
572};
573
575} // namespace auterion
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
Struct describing a camera configuration.
Definition camera.hpp:334
Contains image metadata.
Definition camera.hpp:66
int step
full row size in bytes
Definition camera.hpp:201
std::optional< uint64_t > monotonic_timestamp_us
hardware timestamp [μs]
Definition camera.hpp:205
Encoding
Image encoding, following FourCC.
Definition camera.hpp:70
@ NV12
YUV 4:2:0, https://fourcc.org/pixel-format/yuv-nv12/.
@ Y800
8 bit monochrome image (GREY), https://fourcc.org/pixel-format/yuv-y800/
@ Y16
16 bit monochrome image, https://fourcc.org/pixel-format/yuv-y16/
@ BA81
8-bit Bayer (https://docs.kernel.org/userspace-api/media/v4l/pixfmt-srggb8.html)
@ UYVY
YUV 4:2:2, https://fourcc.org/pixel-format/yuv-uyvy/.
@ YUY2
YUV 4:2:2 (YUYV), https://fourcc.org/pixel-format/yuv-yuy2/.
@ I420
YUV 4:2:0, https://fourcc.org/pixel-format/yuv-i420/.
@ RGBA
32-bit RGBA used for rendering