camera_utilities.h
Go to the documentation of this file.
1 
34 #ifndef MULTISENSE_ROS_CAMERA_UTILITIES_H
35 #define MULTISENSE_ROS_CAMERA_UTILITIES_H
36 
37 #include <tuple>
38 #include <mutex>
39 
40 #include <Eigen/Core>
41 #include <opencv2/opencv.hpp>
42 
43 #include <ros/ros.h>
44 #include <sensor_msgs/CameraInfo.h>
45 
46 #include <multisense_lib/MultiSenseChannel.hh>
47 #include <multisense_lib/MultiSenseTypes.hh>
48 
49 namespace multisense_ros {
50 
52 
54 {
55  cv::Mat map1;
56  cv::Mat map2;
57 };
58 
59 template <typename T>
61 {
62 public:
64  const T &data):
65  driver_(driver),
66  callback_buffer_(driver->reserveCallbackBuffer()),
67  data_(data)
68  {
69  }
70 
72  {
73  driver_->releaseCallbackBuffer(callback_buffer_);
74  }
75 
76  const T &data() const noexcept
77  {
78  return data_;
79  }
80 
81 private:
82 
83  BufferWrapper(const BufferWrapper&) = delete;
84  BufferWrapper operator=(const BufferWrapper&) = delete;
85 
88  const T data_;
89 
90 };
91 
92 template <typename T>
93 constexpr Eigen::Matrix<T, 3, 1> ycbcrToBgr(const crl::multisense::image::Header &luma,
94  const crl::multisense::image::Header &chroma,
95  size_t u,
96  size_t v)
97 {
98  const uint8_t *lumaP = reinterpret_cast<const uint8_t*>(luma.imageDataP);
99  const uint8_t *chromaP = reinterpret_cast<const uint8_t*>(chroma.imageDataP);
100 
101  const size_t luma_offset = (v * luma.width) + u;
102  const size_t chroma_offset = 2 * (((v/2) * (luma.width/2)) + (u/2));
103 
104  const float px_y = static_cast<float>(lumaP[luma_offset]);
105  const float px_cb = static_cast<float>(chromaP[chroma_offset+0]) - 128.0f;
106  const float px_cr = static_cast<float>(chromaP[chroma_offset+1]) - 128.0f;
107 
108  float px_r = px_y + 1.402f * px_cr;
109  float px_g = px_y - 0.34414f * px_cb - 0.71414f * px_cr;
110  float px_b = px_y + 1.772f * px_cb;
111 
112  if (px_r < 0.0f) px_r = 0.0f;
113  else if (px_r > 255.0f) px_r = 255.0f;
114  if (px_g < 0.0f) px_g = 0.0f;
115  else if (px_g > 255.0f) px_g = 255.0f;
116  if (px_b < 0.0f) px_b = 0.0f;
117  else if (px_b > 255.0f) px_b = 255.0f;
118 
119  return Eigen::Matrix<T, 3, 1>{static_cast<T>(px_b), static_cast<T>(px_g), static_cast<T>(px_r)};
120 }
121 
123  const crl::multisense::image::Header &chroma,
124  uint8_t *output);
125 
126 Eigen::Matrix4d makeQ(const crl::multisense::image::Config& config,
127  const crl::multisense::image::Calibration& calibration,
128  const crl::multisense::system::DeviceInfo& device_info);
129 
130 sensor_msgs::CameraInfo makeCameraInfo(const crl::multisense::image::Config& config,
132  const crl::multisense::system::DeviceInfo& device_info,
133  bool scale_calibration);
134 
137  const crl::multisense::system::DeviceInfo& device_info);
139 {
140 public:
141  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
142 
144  const crl::multisense::image::Calibration& calibration,
145  const crl::multisense::system::DeviceInfo& device_info);
146 
147  void updateConfig(const crl::multisense::image::Config& config);
148 
149  crl::multisense::image::Config config() const;
150 
155  Eigen::Matrix4d Q() const;
156 
160  double T() const;
161 
165  double aux_T() const;
166 
170  bool validAux() const;
171 
172  sensor_msgs::CameraInfo leftCameraInfo(const std::string& frame_id, const ros::Time& stamp) const;
173  sensor_msgs::CameraInfo rightCameraInfo(const std::string& frame_id, const ros::Time& stamp) const;
174  sensor_msgs::CameraInfo auxCameraInfo(const std::string& frame_id, const ros::Time& stamp) const;
175 
176  std::shared_ptr<RectificationRemapT> leftRemap() const;
177  std::shared_ptr<RectificationRemapT> rightRemap() const;
178 
179 private:
180 
184 
185  //
186  // Protect our cache during calibration updates
187 
188  mutable std::mutex mutex_;
189 
190  //
191  // Cache for quick queries
192 
193  Eigen::Matrix4d q_matrix_;
194 
195  sensor_msgs::CameraInfo left_camera_info_;
196  sensor_msgs::CameraInfo right_camera_info_;
197  sensor_msgs::CameraInfo aux_camera_info_;
198 
199  std::shared_ptr<RectificationRemapT> left_remap_;
200  std::shared_ptr<RectificationRemapT> right_remap_;
201 };
202 
203 }// namespace
204 
205 #endif
std::shared_ptr< RectificationRemapT > right_remap_
sensor_msgs::CameraInfo makeCameraInfo(const crl::multisense::image::Config &config, const crl::multisense::image::Calibration::Data &calibration, const crl::multisense::system::DeviceInfo &device_info, bool scale_calibration)
f
RectificationRemapT makeRectificationRemap(const crl::multisense::image::Config &config, const crl::multisense::image::Calibration::Data &calibration, const crl::multisense::system::DeviceInfo &device_info)
crl::multisense::Channel * driver_
crl::multisense::image::Config config_
const crl::multisense::system::DeviceInfo & device_info_
Eigen::Matrix4d makeQ(const crl::multisense::image::Config &config, const crl::multisense::image::Calibration &calibration, const crl::multisense::system::DeviceInfo &device_info)
constexpr Eigen::Matrix< T, 3, 1 > ycbcrToBgr(const crl::multisense::image::Header &luma, const crl::multisense::image::Header &chroma, size_t u, size_t v)
const crl::multisense::image::Calibration calibration_
const T & data() const noexcept
BufferWrapper(crl::multisense::Channel *driver, const T &data)
std::shared_ptr< RectificationRemapT > left_remap_
sensor_msgs::CameraInfo right_camera_info_


multisense_ros
Author(s):
autogenerated on Sun Mar 14 2021 02:34:55