35 #include <tf2_ros/transform_listener.h>
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>
43 #include <opencv2/core/mat.hpp>
44 #include <rclcpp/rclcpp.hpp>
45 #include <sensor_msgs/msg/camera_info.hpp>
53 using namespace std::chrono_literals;
56 class CameraMonitorImpl;
84 ImageHeader(
int width_,
int height_, Encoding encoding_,
int step_ = 0);
86 template <
typename ImageT = auterion_core_msgs::msg::Image8m>
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()),
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") {
104 encoding = Encoding::I420;
105 }
else if (encoding_str ==
"nv12") {
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;
123 template <
typename ImageT = auterion_core_msgs::msg::Image8m>
124 void toImage(ImageT& image) {
126 image.height = height;
128 image.stamp = timestamp;
130 case Encoding::Unknown:
131 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"unknown",
132 image.encoding.size());
135 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"mono8",
136 image.encoding.size());
139 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"mono16",
140 image.encoding.size());
143 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"uyvy",
144 image.encoding.size());
147 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"yuyv",
148 image.encoding.size());
151 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"i420",
152 image.encoding.size());
155 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"nv12",
156 image.encoding.size());
159 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"rgb8",
160 image.encoding.size());
163 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bgr8",
164 image.encoding.size());
167 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_bggr8",
168 image.encoding.size());
171 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_gbrg8",
172 image.encoding.size());
175 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_grbg8",
176 image.encoding.size());
179 strncpy(
reinterpret_cast<char*
>(image.encoding.data()),
"bayer_rggb8",
180 image.encoding.size());
185 size_t planeOffset(
int plane)
const;
186 size_t planeSizeBytes(
int plane)
const;
187 size_t imageSizeBytes()
const;
192 Encoding encoding{Encoding::Unknown};
193 rclcpp::Time timestamp{};
204 Image(
ImageHeader header, uint8_t* data) : _header(std::move(header)), _data(data) {}
206 const ImageHeader& header()
const {
return _header; }
208 uint8_t* data() {
return _data; }
209 const uint8_t* data()
const {
return _data; }
211 int width()
const {
return _header.width; }
212 int height()
const {
return _header.height; }
222 uint8_t* _data{
nullptr};
230 enum class SensorType {
238 enum class MountOrientation {
248 enum class MountOrientationDetail {
255 enum class PrimaryPurpose {
265 Eigen::Quaterniond rotation{-0.5, 0.5, -0.5, 0.5};
266 Eigen::Vector3d translation{0.0, 0.0, 0.0};
270 explicit CameraDescriptor(
const auterion_core_msgs::msg::CameraInfo& camera_info);
272 operator auterion_core_msgs::msg::CameraInfo()
const;
274 std::string unique_name;
276 std::string camera_model;
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;
295 const NotificationCallback& on_camera_removed =
nullptr);
300 std::shared_ptr<CameraMonitorImpl> _impl;
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);
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(
328 const std::chrono::seconds& timeout = 30s);
329 static std::optional<Camera> openFirst(
SDK& sdk,
const std::chrono::seconds& timeout = 30s);
331 using ImageCallback = std::function<void(
const Image& image)>;
340 void subscribeCameraInfo(
341 std::function<
void(
const sensor_msgs::msg::CameraInfo::SharedPtr)> callback);
378 bool getPoseBodyCamera(Eigen::Quaterniond& q_body_camera, Eigen::Vector3d& t_body_camera)
const;
399 const tf2::TimePoint& time = tf2::TimePointZero)
const;
412 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: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
Definition: camera.hpp:264
Struct describing a camera configuration.
Definition: camera.hpp:229