Auterion App SDK
Auterion SDK is a library that can be used by AuterionOS apps to communicate with the system.
camera.hpp
1 /****************************************************************************
2  *
3  * Copyright 2023 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 #include <tf2_ros/transform_listener.h>
36 
37 #include <Eigen/Eigen>
38 #include <auterion_core_msgs/msg/camera_info.hpp>
39 #include <auterion_core_msgs/msg/image1m.hpp>
40 #include <auterion_core_msgs/msg/image8m.hpp>
41 #include <chrono>
42 #include <functional>
43 #include <opencv2/core/mat.hpp>
44 #include <rclcpp/rclcpp.hpp>
45 #include <sensor_msgs/msg/camera_info.hpp>
46 #include <string>
47 #include <utility>
48 
49 namespace auterion {
53 using namespace std::chrono_literals;
54 
55 class SDK;
56 class CameraMonitorImpl;
57 class CameraImpl;
58 
63 struct ImageHeader {
64  ImageHeader() = default;
65 
67  enum class Encoding {
68  Unknown,
69  Y800,
70  Y16,
71  UYVY,
72  YUY2,
73  I420,
74  NV12,
75  RGB8,
76  BGR8,
78  BA81,
79  GBRG,
80  GRBG,
81  RGGB,
82  };
83 
84  ImageHeader(int width_, int height_, Encoding encoding_, int step_ = 0);
85 
86  template <typename ImageT = auterion_core_msgs::msg::Image8m>
87  explicit ImageHeader(const ImageT& image)
88  : width(image.width), height(image.height), step(image.step), timestamp(image.stamp) {
89  const int encoding_len =
90  strnlen(reinterpret_cast<const char*>(image.encoding.data()), image.encoding.size());
91  const std::string encoding_str(reinterpret_cast<const char*>(image.encoding.data()),
92  encoding_len);
93  if (encoding_str == "mono8") {
94  encoding = Encoding::Y800;
95  } else if (encoding_str == "mono16") {
96  encoding = Encoding::Y16;
97  } else if (encoding_str == "uyvy") {
98  encoding = Encoding::UYVY;
99  } else if (encoding_str == "yuyv") {
100  encoding = Encoding::YUY2;
101  } else if (encoding_str == "i420") {
102  // (This does not exist in ROS:
103  // https://github.com/ros2/common_interfaces/blob/master/sensor_msgs/include/sensor_msgs/image_encodings.hpp)
104  encoding = Encoding::I420;
105  } else if (encoding_str == "nv12") {
106  // Does not exist in ROS 2
107  encoding = Encoding::NV12;
108  } else if (encoding_str == "rgb8") {
109  encoding = Encoding::RGB8;
110  } else if (encoding_str == "bgr8") {
111  encoding = Encoding::BGR8;
112  } else if (encoding_str == "bayer_bggr8") {
113  encoding = Encoding::BA81;
114  } else if (encoding_str == "bayer_gbrg8") {
115  encoding = Encoding::GBRG;
116  } else if (encoding_str == "bayer_grbg8") {
117  encoding = Encoding::GRBG;
118  } else if (encoding_str == "bayer_rggb8") {
119  encoding = Encoding::RGGB;
120  }
121  }
122 
123  template <typename ImageT = auterion_core_msgs::msg::Image8m>
124  void toImage(ImageT& image) {
125  image.width = width;
126  image.height = height;
127  image.step = step;
128  image.stamp = timestamp;
129  switch (encoding) {
130  case Encoding::Unknown:
131  strncpy(reinterpret_cast<char*>(image.encoding.data()), "unknown",
132  image.encoding.size());
133  break;
134  case Encoding::Y800:
135  strncpy(reinterpret_cast<char*>(image.encoding.data()), "mono8",
136  image.encoding.size());
137  break;
138  case Encoding::Y16:
139  strncpy(reinterpret_cast<char*>(image.encoding.data()), "mono16",
140  image.encoding.size());
141  break;
142  case Encoding::UYVY:
143  strncpy(reinterpret_cast<char*>(image.encoding.data()), "uyvy",
144  image.encoding.size());
145  break;
146  case Encoding::YUY2:
147  strncpy(reinterpret_cast<char*>(image.encoding.data()), "yuyv",
148  image.encoding.size());
149  break;
150  case Encoding::I420:
151  strncpy(reinterpret_cast<char*>(image.encoding.data()), "i420",
152  image.encoding.size());
153  break;
154  case Encoding::NV12:
155  strncpy(reinterpret_cast<char*>(image.encoding.data()), "nv12",
156  image.encoding.size());
157  break;
158  case Encoding::RGB8:
159  strncpy(reinterpret_cast<char*>(image.encoding.data()), "rgb8",
160  image.encoding.size());
161  break;
162  case Encoding::BGR8:
163  strncpy(reinterpret_cast<char*>(image.encoding.data()), "bgr8",
164  image.encoding.size());
165  break;
166  case Encoding::BA81:
167  strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_bggr8",
168  image.encoding.size());
169  break;
170  case Encoding::GBRG:
171  strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_gbrg8",
172  image.encoding.size());
173  break;
174  case Encoding::GRBG:
175  strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_grbg8",
176  image.encoding.size());
177  break;
178  case Encoding::RGGB:
179  strncpy(reinterpret_cast<char*>(image.encoding.data()), "bayer_rggb8",
180  image.encoding.size());
181  break;
182  }
183  }
184 
185  size_t planeOffset(int plane) const;
186  size_t planeSizeBytes(int plane) const;
187  size_t imageSizeBytes() const;
188 
189  int width{};
190  int height{};
191  int step{};
192  Encoding encoding{Encoding::Unknown};
193  rclcpp::Time timestamp{};
194 };
195 
196 std::ostream& operator<<(std::ostream& os, const ImageHeader::Encoding& encoding);
197 
202 class Image {
203  public:
204  Image(ImageHeader header, uint8_t* data) : _header(std::move(header)), _data(data) {}
205 
206  const ImageHeader& header() const { return _header; }
207 
208  uint8_t* data() { return _data; }
209  const uint8_t* data() const { return _data; }
210 
211  int width() const { return _header.width; }
212  int height() const { return _header.height; }
213 
218  cv::Mat asOpenCVMat(int plane = -1) const;
219 
220  private:
221  ImageHeader _header{};
222  uint8_t* _data{nullptr};
223 };
224 
230  enum class SensorType {
231  Unknown = 0,
232  Monochrome = 1,
233  RGB = 2,
234  Depth = 3,
235  RGBD = 4,
236  IR = 5,
237  };
238  enum class MountOrientation {
239  Unknown = 0,
240  Dynamic = 1,
241  Forward = 2,
242  Backward = 3,
243  Upward = 4,
244  Downward = 5,
245  Leftward = 6,
246  Rightward = 7,
247  };
248  enum class MountOrientationDetail {
249  Unknown = 0,
250  Left = 1,
251  Right = 2,
252  Upper = 3,
253  Lower = 4,
254  };
255  enum class PrimaryPurpose {
256  Unknown = 0,
257  Generic = 1,
258  OpticalFlow = 2,
259  VIO = 3,
260  FPV = 4,
261  Survey = 5,
262  Tracking = 6,
263  };
265  Eigen::Quaterniond rotation{-0.5, 0.5, -0.5, 0.5}; // {q, x, y, z} default front facing
266  Eigen::Vector3d translation{0.0, 0.0, 0.0};
267  };
268 
269  CameraDescriptor() = default;
270  explicit CameraDescriptor(const auterion_core_msgs::msg::CameraInfo& camera_info);
271 
272  operator auterion_core_msgs::msg::CameraInfo() const;
273 
274  std::string unique_name;
275 
276  std::string camera_model;
277 
278  SensorType sensor_type{SensorType::Unknown};
279  MountOrientation mount_orientation{MountOrientation::Unknown};
280  MountOrientationDetail mount_orientation_detail{MountOrientationDetail::Unknown};
281  PrimaryPurpose primary_purpose{PrimaryPurpose::Unknown};
282  ExtrinsicCalibration extrinsic_calibration;
283 };
284 
291  public:
292  using NotificationCallback = std::function<void(const CameraDescriptor&)>;
293 
294  CameraMonitor(SDK& sdk, const NotificationCallback& on_camera_added,
295  const NotificationCallback& on_camera_removed = nullptr);
296 
297  ~CameraMonitor() = default;
298 
299  private:
300  std::shared_ptr<CameraMonitorImpl> _impl;
301 };
302 
307 class Camera {
308  public:
309  Camera(SDK& sdk, const CameraDescriptor& camera_descriptor);
310  ~Camera() = default;
311 
315  static Camera waitForCamera(SDK& sdk,
316  const std::function<bool(const CameraDescriptor&)>& find_callback);
317 
318  [[deprecated(
319  "waitForCamera with 'camera_descriptor' not used anymore. This will be removed in some "
320  "later release.")]] static Camera
321  waitForCamera(SDK& sdk,
322  std::optional<auterion::CameraDescriptor> camera_descriptor = std::nullopt);
323 
324  static std::optional<Camera> open(SDK& sdk, const std::string& unique_name,
325  const std::chrono::seconds& timeout = 30s);
326  static std::optional<Camera> open(
327  SDK& sdk, const std::function<bool(const CameraDescriptor&)>& find_callback,
328  const std::chrono::seconds& timeout = 30s);
329  static std::optional<Camera> openFirst(SDK& sdk, const std::chrono::seconds& timeout = 30s);
330 
331  using ImageCallback = std::function<void(const Image& image)>;
332 
338  void subscribeImage(const ImageCallback& callback);
339 
340  void subscribeCameraInfo(
341  std::function<void(const sensor_msgs::msg::CameraInfo::SharedPtr)> callback);
342 
348  bool cameraInfoValid() const;
349 
354  std::optional<cv::Size> getLastImageSize() const;
355 
362  Eigen::Vector3d unprojectImagePoint(const cv::Point& image_point) const;
363 
378  bool getPoseBodyCamera(Eigen::Quaterniond& q_body_camera, Eigen::Vector3d& t_body_camera) const;
379 
398  bool getPoseWorldCamera(Eigen::Quaterniond& q_enu_camera, Eigen::Vector3d& t_enu_camera,
399  const tf2::TimePoint& time = tf2::TimePointZero) const;
400 
407  bool getCameraInfo(sensor_msgs::msg::CameraInfo& camera_info) const;
408 
409  const CameraDescriptor& descriptor() const;
410 
411  private:
412  std::shared_ptr<CameraImpl> _impl;
413 };
414 
416 } // namespace auterion
Monitor for new or removed cameras. This will also list all existing cameras upon creating the object...
Definition: camera.hpp:290
Camera client to subscribe to a camera image stream.
Definition: camera.hpp:307
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)
std::optional< cv::Size > getLastImageSize() const
Returns the last image size based on the camera image message.
Eigen::Vector3d unprojectImagePoint(const cv::Point &image_point) const
Determine the (relative) camera-frame 3D position of a point in an image.
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.
Contains image data with a specific encoding.
Definition: camera.hpp:202
cv::Mat asOpenCVMat(int plane=-1) const
SDK execution class. All callbacks are called on the same thread.
Definition: auterion.hpp:45
Struct describing a camera configuration.
Definition: camera.hpp:229
Contains image metadata.
Definition: camera.hpp:63
Encoding
Image encoding, following FourCC.
Definition: camera.hpp:67