LibMultiSense
LibMultiSense Documentation
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Pages
MultiSenseUtilities.hh
Go to the documentation of this file.
1 
37 #pragma once
38 
39 #include <array>
40 #include <filesystem>
41 #include <fstream>
42 #include <sstream>
43 #include <vector>
44 
45 #include "MultiSenseTypes.hh"
46 
47 namespace multisense
48 {
49 
54 #pragma pack(push, 1)
55 
59 template<typename Color>
60 struct Point
61 {
62  float x = 0;
63  float y = 0;
64  float z = 0;
65  Color color;
66 };
67 
71 template<>
72 struct Point<void>
73 {
74  float x = 0;
75  float y = 0;
76  float z = 0;
77 };
78 
79 template<typename Color = void>
80 struct PointCloud
81 {
82  std::vector<Point<Color>> cloud;
83 };
84 
85 #pragma pack(pop)
86 
90 MULTISENSE_API std::string to_string(const Status &status);
91 
96 MULTISENSE_API bool write_image(const Image &image, const std::filesystem::path &path);
97 
104 MULTISENSE_API std::optional<Image> create_depth_image(const ImageFrame &frame,
105  const Image::PixelFormat &depth_format,
106  const DataSource &disparity_source = DataSource::LEFT_DISPARITY_RAW,
107  float invalid_value = 0);
108 
112 MULTISENSE_API std::optional<Image> create_bgr_from_ycbcr420(const Image &luma,
113  const Image &chroma,
114  const DataSource &output_source);
115 
119 MULTISENSE_API std::optional<Image> create_bgr_image(const ImageFrame &frame,
120  const DataSource &output_source);
121 
125 template<typename Color>
126 MULTISENSE_API std::optional<PointCloud<Color>> create_color_pointcloud(const Image &disparity,
127  const std::optional<Image> &color,
128  double max_range,
129  const StereoCalibration &calibration)
130 {
131  size_t color_step = 0;
132  double color_disparity_scale = 0.0;
133 
134  if constexpr (std::is_same_v<Color, void>)
135  {
136  if (disparity.format != Image::PixelFormat::MONO16 || disparity.width < 0 || disparity.height < 0)
137  {
138  return std::nullopt;
139  }
140  }
141  else
142  {
143  if (!color)
144  {
145  return std::nullopt;
146  }
147 
148  color_step = sizeof(Color);
149 
150  if (disparity.format != Image::PixelFormat::MONO16 ||
151  color->width != disparity.width ||
152  color->height != disparity.height ||
153  disparity.width < 0 ||
154  disparity.height < 0)
155  {
156  return std::nullopt;
157  }
158 
159  const double tx = calibration.right.P[0][3] / calibration.right.P[0][0];
160  const double color_tx = color->calibration.P[0][3] / color->calibration.P[0][0];
161  color_disparity_scale = color_tx / tx;
162  }
163 
164  constexpr double scale = 1.0 / 16.0;
165 
166  const double squared_range = max_range * max_range;
167 
168  const double fx = disparity.calibration.P[0][0];
169  const double fy = disparity.calibration.P[1][1];
170  const double cx = disparity.calibration.P[0][2];
171  const double cy = disparity.calibration.P[1][2];
172  const double tx = calibration.right.P[0][3] / calibration.right.P[0][0];
173  const double cx_prime = calibration.right.P[0][2];
174 
175  const double fytx = fy * tx;
176  const double fxtx = fx * tx;
177 
178  const double fycxtx = fy * cx * tx;
179  const double fxcytx = fx * cy * tx;
180  const double fxfytx = fx * fy * tx;
181  const double fycxcxprime = fy * (cx - cx_prime);
182 
183  PointCloud<Color> output;
184  output.cloud.reserve(disparity.width * disparity.height);
185 
186  for (size_t h = 0 ; h < static_cast<size_t>(disparity.height) ; ++h)
187  {
188  for (size_t w = 0 ; w < static_cast<size_t>(disparity.width) ; ++w)
189  {
190  const size_t index = disparity.image_data_offset +
191  (h * disparity.width * sizeof(uint16_t)) +
192  (w * sizeof(uint16_t));
193 
194  const double d =
195  static_cast<double>(*reinterpret_cast<const uint16_t*>(disparity.raw_data->data() + index)) * scale;
196 
197  if (d == 0.0)
198  {
199  continue;
200  }
201 
202  const double inversebeta = 1.0 / (-fy * d + fycxcxprime);
203  const double x = ((fytx * w) + (-fycxtx)) * inversebeta;
204  const double y = ((fxtx * h) + (-fxcytx)) * inversebeta;
205  const double z = fxfytx * inversebeta;
206 
207  if ((x*x + y*y + z*z) > squared_range)
208  {
209  continue;
210  }
211 
212  if constexpr (std::is_same_v<Color, void>)
213  {
214  output.cloud.push_back(Point<Color>{static_cast<float>(x), static_cast<float>(y), static_cast<float>(z)});
215  }
216  else
217  {
218  //
219  // Use the approximation that color_pixel_u = disp_u - (tx_color/ tx) * d
220  //
221  const size_t color_index = color->image_data_offset +
222  (h * color->width * color_step) +
223  static_cast<size_t>((static_cast<double>(w) - (color_disparity_scale * d))) * color_step;
224 
225  const Color color_pixel = *reinterpret_cast<const Color*>(color->raw_data->data() + color_index);
226 
227  output.cloud.push_back(Point<Color>{static_cast<float>(x), static_cast<float>(y), static_cast<float>(z),
228  color_pixel});
229  }
230  }
231  }
232 
233  return output;
234 }
235 
239 template<typename Color>
240 MULTISENSE_API std::optional<PointCloud<Color>> create_color_pointcloud(const ImageFrame &frame,
241  double max_range,
242  const DataSource &color_source = DataSource::UNKNOWN,
243  const DataSource &disparity_source = DataSource::LEFT_DISPARITY_RAW)
244 {
245  if constexpr (std::is_same_v<Color, void>)
246  {
247  if (!frame.has_image(disparity_source))
248  {
249  return std::nullopt;
250  }
251 
252  return create_color_pointcloud<Color>(frame.get_image(disparity_source), std::nullopt, max_range, frame.calibration);
253  }
254  else
255  {
256  if (!frame.has_image(color_source) || !frame.has_image(disparity_source))
257  {
258  return std::nullopt;
259  }
260 
261  return create_color_pointcloud<Color>(frame.get_image(disparity_source),
262  frame.get_image(color_source),
263  max_range,
264  frame.calibration);
265  }
266 }
267 
268 MULTISENSE_API std::optional<PointCloud<void>> create_pointcloud(const ImageFrame &frame,
269  double max_range,
270  const DataSource &disparity_source = DataSource::LEFT_DISPARITY_RAW);
271 
275 template <typename Color>
276 MULTISENSE_API bool write_pointcloud_ply(const PointCloud<Color> &point_cloud, const std::filesystem::path &path)
277 {
278  std::ofstream ply(path, std::ios::binary);
279  if (!ply.good())
280  {
281  return false;
282  }
283 
284  std::ostringstream header;
285  header << "ply\n";
286  header << "format binary_little_endian 1.0\n";
287  header << "element vertex " << point_cloud.cloud.size() << "\n";
288  header << "property float x\n";
289  header << "property float y\n";
290  header << "property float z\n";
291 
292  if constexpr (std::is_same_v<Color, uint8_t>)
293  {
294  header << "property uchar intensity\n";
295  }
296  else if constexpr (std::is_same_v<Color, uint16_t>)
297  {
298  header << "property ushort intensity\n";
299  }
300  else if constexpr (std::is_same_v<Color, std::array<uint8_t, 3>>)
301  {
302  header << "property uchar red\n";
303  header << "property uchar green\n";
304  header << "property uchar blue\n";
305  }
306  else if (!std::is_same_v<Color, void>)
307  {
308  throw std::runtime_error("Unsupported color type");
309  }
310 
311  header << "end_header\n";
312 
313  std::string header_str = header.str();
314  ply.write(header_str.c_str(), header_str.size());
315 
316  for (const auto &point : point_cloud.cloud)
317  {
318  ply.write(reinterpret_cast<const char*>(&point.x), sizeof(point.x));
319  ply.write(reinterpret_cast<const char*>(&point.y), sizeof(point.y));
320  ply.write(reinterpret_cast<const char*>(&point.z), sizeof(point.z));
321 
322  if constexpr (std::is_same_v<Color, std::array<uint8_t, 3>>)
323  {
324  uint8_t red = point.color[2];
325  uint8_t green = point.color[1];
326  uint8_t blue = point.color[0];
327  ply.write(reinterpret_cast<const char*>(&red), sizeof(red));
328  ply.write(reinterpret_cast<const char*>(&green), sizeof(green));
329  ply.write(reinterpret_cast<const char*>(&blue), sizeof(blue));
330  }
331  else if constexpr (std::is_same_v<Color, void>)
332  {
333  // No color data to write.
334  }
335  else
336  {
337  // Write the color value directly (works for uint8_t or uint16_t).
338  ply.write(reinterpret_cast<const char*>(&point.color), sizeof(point.color));
339  }
340  }
341 
342  return true;
343 }
344 
345 }
multisense::Point
Make sure our Points and point clouds are packed for applications which might need to handle the unde...
Definition: MultiSenseUtilities.hh:60
multisense::Image::format
PixelFormat format
The format of the image data stored in the raw_data stored in the raw_data buffer.
Definition: MultiSenseTypes.hh:221
multisense::ImageFrame
A frame containing multiple images (indexed by DataSource).
Definition: MultiSenseTypes.hh:300
multisense::ImageFrame::get_image
const Image & get_image(const DataSource &source) const
Retrieve image by DataSource.
Definition: MultiSenseTypes.hh:313
multisense::Status
Status
Definition: MultiSenseTypes.hh:67
MULTISENSE_API
#define MULTISENSE_API
Definition: MultiSenseTypes.hh:57
multisense::Point::color
Color color
Definition: MultiSenseUtilities.hh:65
multisense::PointCloud
Definition: MultiSenseUtilities.hh:80
multisense::StereoCalibration::right
CameraCalibration right
Calibration information for the right camera.
Definition: MultiSenseTypes.hh:176
multisense::Image::PixelFormat
PixelFormat
Pixel formats.
Definition: MultiSenseTypes.hh:192
multisense::PointCloud::cloud
std::vector< Point< Color > > cloud
Definition: MultiSenseUtilities.hh:82
multisense::create_bgr_image
MULTISENSE_API std::optional< Image > create_bgr_image(const ImageFrame &frame, const DataSource &output_source)
Convert a YCbCr420 luma + chroma image into a BGR color image.
multisense::create_bgr_from_ycbcr420
MULTISENSE_API std::optional< Image > create_bgr_from_ycbcr420(const Image &luma, const Image &chroma, const DataSource &output_source)
Convert a YCbCr420 luma + chroma image into a BGR color image.
MultiSenseTypes.hh
multisense::DataSource
DataSource
Identifies which camera or data source the image is from.
Definition: MultiSenseTypes.hh:83
multisense::Image::calibration
CameraCalibration calibration
The scaled calibration associated with the image.
Definition: MultiSenseTypes.hh:253
multisense::create_color_pointcloud
MULTISENSE_API std::optional< PointCloud< Color > > create_color_pointcloud(const Image &disparity, const std::optional< Image > &color, double max_range, const StereoCalibration &calibration)
Create a point cloud from a image frame and a color source.
Definition: MultiSenseUtilities.hh:126
multisense::Point::x
float x
Definition: MultiSenseUtilities.hh:62
multisense::Image::width
int width
Width of the image in pixels.
Definition: MultiSenseTypes.hh:226
multisense::Image::PixelFormat::MONO16
@ MONO16
multisense::write_pointcloud_ply
MULTISENSE_API bool write_pointcloud_ply(const PointCloud< Color > &point_cloud, const std::filesystem::path &path)
Write a point cloud to a ASCII ply file.
Definition: MultiSenseUtilities.hh:276
multisense::StereoCalibration
Definition: MultiSenseTypes.hh:166
multisense::Point::y
float y
Definition: MultiSenseUtilities.hh:63
multisense::Image::raw_data
std::shared_ptr< const std::vector< uint8_t > > raw_data
A pointer to the raw image data sent from the camera.
Definition: MultiSenseTypes.hh:206
multisense::Image::image_data_offset
int64_t image_data_offset
An offset into the raw_data pointer where the image data starts.
Definition: MultiSenseTypes.hh:211
multisense
Definition: MultiSenseChannel.hh:44
multisense::Point::z
float z
Definition: MultiSenseUtilities.hh:64
multisense::Image::height
int height
Height of the image in pixels.
Definition: MultiSenseTypes.hh:231
multisense::ImageFrame::calibration
StereoCalibration calibration
The scaled calibration for the entire camera.
Definition: MultiSenseTypes.hh:344
multisense::create_depth_image
MULTISENSE_API std::optional< Image > create_depth_image(const ImageFrame &frame, const Image::PixelFormat &depth_format, const DataSource &disparity_source=DataSource::LEFT_DISPARITY_RAW, float invalid_value=0)
Create a depth image from a image frame.
multisense::write_image
MULTISENSE_API bool write_image(const Image &image, const std::filesystem::path &path)
Write a image to a specific path on disk.
multisense::Image
Represents a single image plus metadata.
Definition: MultiSenseTypes.hh:187
multisense::CameraCalibration::P
std::array< std::array< float, 4 >, 3 > P
Rectified projection matrix which takes points in the origin camera coordinate frame and projects the...
Definition: MultiSenseTypes.hh:142
multisense::create_pointcloud
MULTISENSE_API std::optional< PointCloud< void > > create_pointcloud(const ImageFrame &frame, double max_range, const DataSource &disparity_source=DataSource::LEFT_DISPARITY_RAW)
multisense::DataSource::UNKNOWN
@ UNKNOWN
multisense::to_string
MULTISENSE_API std::string to_string(const Status &status)
Convert a status object to a user readable string.
multisense::ImageFrame::has_image
bool has_image(const DataSource &source) const
Check if we have an image for a given data source.
Definition: MultiSenseTypes.hh:326
multisense::DataSource::LEFT_DISPARITY_RAW
@ LEFT_DISPARITY_RAW