Azure Kinect Sensor SDK  refs/heads/release/1.4.x
Documentation for https://github.com/Microsoft/Azure-Kinect-Sensor-SDK
k4a.hpp
1 
7 #ifndef K4A_HPP
8 #define K4A_HPP
9 
10 #include "k4a.h"
11 
12 #include <algorithm>
13 #include <chrono>
14 #include <cstdint>
15 #include <limits>
16 #include <stdexcept>
17 #include <string>
18 #include <vector>
19 
20 namespace k4a
21 {
22 
33 class error : public std::runtime_error
34 {
35 public:
36  using runtime_error::runtime_error;
37 };
38 
39 // Helper functions not intended for use by client code
40 //
41 namespace internal
42 {
44 
51 template<typename output_type, typename input_type> output_type clamp_cast(input_type input)
52 {
53  static_assert(std::is_arithmetic<input_type>::value, "clamp_cast only supports arithmetic types");
54  static_assert(std::is_arithmetic<output_type>::value, "clamp_cast only supports arithmetic types");
55  const input_type min_value = std::is_signed<input_type>() ?
56  static_cast<input_type>(std::numeric_limits<output_type>::min()) :
57  0;
58 
59  input_type max_value = static_cast<input_type>(std::numeric_limits<output_type>::max());
60  if (max_value < 0)
61  {
62  // Output type is of greater or equal size to input type and we've overflowed.
63  //
64  max_value = std::numeric_limits<input_type>::max();
65  }
66  input = std::min(input, max_value);
67  input = std::max(input, min_value);
68  return static_cast<output_type>(input);
69 }
71 } // namespace internal
72 
80 class image
81 {
82 public:
88  image(k4a_image_t handle = nullptr) noexcept : m_handle(handle) {}
89 
92  image(const image &other) noexcept : m_handle(other.m_handle)
93  {
94  if (m_handle != nullptr)
95  {
96  k4a_image_reference(m_handle);
97  }
98  }
99 
102  image(image &&other) noexcept : m_handle(other.m_handle)
103  {
104  other.m_handle = nullptr;
105  }
106 
107  ~image()
108  {
109  reset();
110  }
111 
114  image &operator=(const image &other) noexcept
115  {
116  if (this != &other)
117  {
118  reset();
119  m_handle = other.m_handle;
120  if (m_handle != nullptr)
121  {
122  k4a_image_reference(m_handle);
123  }
124  }
125  return *this;
126  }
127 
130  image &operator=(image &&other) noexcept
131  {
132  if (this != &other)
133  {
134  reset();
135  m_handle = other.m_handle;
136  other.m_handle = nullptr;
137  }
138  return *this;
139  }
140 
143  image &operator=(std::nullptr_t) noexcept
144  {
145  reset();
146  return *this;
147  }
148 
151  bool operator==(const image &other) const noexcept
152  {
153  return m_handle == other.m_handle;
154  }
155 
158  bool operator==(std::nullptr_t) const noexcept
159  {
160  return m_handle == nullptr;
161  }
162 
165  bool operator!=(const image &other) const noexcept
166  {
167  return m_handle != other.m_handle;
168  }
169 
172  bool operator!=(std::nullptr_t) const noexcept
173  {
174  return m_handle != nullptr;
175  }
176 
179  explicit operator bool() const noexcept
180  {
181  return is_valid();
182  }
183 
186  bool is_valid() const noexcept
187  {
188  return m_handle != nullptr;
189  }
190 
198  k4a_image_t handle() const noexcept
199  {
200  return m_handle;
201  }
202 
205  void reset() noexcept
206  {
207  if (m_handle != nullptr)
208  {
209  k4a_image_release(m_handle);
210  m_handle = nullptr;
211  }
212  }
213 
219  static image create(k4a_image_format_t format, int width_pixels, int height_pixels, int stride_bytes)
220  {
221  k4a_image_t handle = nullptr;
222  k4a_result_t result = k4a_image_create(format, width_pixels, height_pixels, stride_bytes, &handle);
223  if (K4A_RESULT_SUCCEEDED != result)
224  {
225  throw error("Failed to create image!");
226  }
227  return image(handle);
228  }
229 
236  int width_pixels,
237  int height_pixels,
238  int stride_bytes,
239  uint8_t *buffer,
240  size_t buffer_size,
241  k4a_memory_destroy_cb_t *buffer_release_cb,
242  void *buffer_release_cb_context)
243  {
244  k4a_image_t handle = nullptr;
245  k4a_result_t result = k4a_image_create_from_buffer(format,
246  width_pixels,
247  height_pixels,
248  stride_bytes,
249  buffer,
250  buffer_size,
251  buffer_release_cb,
252  buffer_release_cb_context,
253  &handle);
254  if (K4A_RESULT_SUCCEEDED != result)
255  {
256  throw error("Failed to create image from buffer");
257  }
258  return image(handle);
259  }
260 
265  uint8_t *get_buffer() noexcept
266  {
267  return k4a_image_get_buffer(m_handle);
268  }
269 
274  const uint8_t *get_buffer() const noexcept
275  {
276  return k4a_image_get_buffer(m_handle);
277  }
278 
283  size_t get_size() const noexcept
284  {
285  return k4a_image_get_size(m_handle);
286  }
287 
293  {
294  return k4a_image_get_format(m_handle);
295  }
296 
301  int get_width_pixels() const noexcept
302  {
303  return k4a_image_get_width_pixels(m_handle);
304  }
305 
310  int get_height_pixels() const noexcept
311  {
312  return k4a_image_get_height_pixels(m_handle);
313  }
314 
319  int get_stride_bytes() const noexcept
320  {
321  return k4a_image_get_stride_bytes(m_handle);
322  }
323 
328  std::chrono::microseconds get_device_timestamp() const noexcept
329  {
330  return std::chrono::microseconds(k4a_image_get_device_timestamp_usec(m_handle));
331  }
332 
337  std::chrono::nanoseconds get_system_timestamp() const noexcept
338  {
339  return std::chrono::nanoseconds(k4a_image_get_system_timestamp_nsec(m_handle));
340  }
341 
346  std::chrono::microseconds get_exposure() const noexcept
347  {
348  return std::chrono::microseconds(k4a_image_get_exposure_usec(m_handle));
349  }
350 
355  uint32_t get_white_balance() const noexcept
356  {
357  return k4a_image_get_white_balance(m_handle);
358  }
359 
364  uint32_t get_iso_speed() const noexcept
365  {
366  return k4a_image_get_iso_speed(m_handle);
367  }
368 
373  void set_timestamp(std::chrono::microseconds timestamp) noexcept
374  {
375  k4a_image_set_device_timestamp_usec(m_handle, internal::clamp_cast<uint64_t>(timestamp.count()));
376  }
377 
382  void set_exposure_time(std::chrono::microseconds exposure) noexcept
383  {
384  k4a_image_set_exposure_usec(m_handle, internal::clamp_cast<uint64_t>(exposure.count()));
385  }
386 
391  void set_white_balance(uint32_t white_balance) noexcept
392  {
393  k4a_image_set_white_balance(m_handle, white_balance);
394  }
395 
400  void set_iso_speed(uint32_t iso_speed) noexcept
401  {
402  k4a_image_set_iso_speed(m_handle, iso_speed);
403  }
404 
405 private:
406  k4a_image_t m_handle;
407 };
408 
414 class capture
415 {
416 public:
422  capture(k4a_capture_t handle = nullptr) noexcept : m_handle(handle) {}
423 
426  capture(const capture &other) noexcept : m_handle(other.m_handle)
427  {
428  if (m_handle != nullptr)
429  {
430  k4a_capture_reference(m_handle);
431  }
432  }
433 
436  capture(capture &&other) noexcept : m_handle(other.m_handle)
437  {
438  other.m_handle = nullptr;
439  }
440 
441  ~capture()
442  {
443  reset();
444  }
445 
448  capture &operator=(const capture &other) noexcept
449  {
450  if (this != &other)
451  {
452  reset();
453  m_handle = other.m_handle;
454  if (m_handle != nullptr)
455  {
456  k4a_capture_reference(m_handle);
457  }
458  }
459  return *this;
460  }
461 
464  capture &operator=(capture &&other) noexcept
465  {
466  if (this != &other)
467  {
468  reset();
469  m_handle = other.m_handle;
470  other.m_handle = nullptr;
471  }
472  return *this;
473  }
474 
477  capture &operator=(std::nullptr_t) noexcept
478  {
479  reset();
480  return *this;
481  }
482 
485  bool operator==(const capture &other) const noexcept
486  {
487  return m_handle == other.m_handle;
488  }
489 
492  bool operator==(std::nullptr_t) const noexcept
493  {
494  return m_handle == nullptr;
495  }
496 
499  bool operator!=(const capture &other) const noexcept
500  {
501  return m_handle != other.m_handle;
502  }
503 
506  bool operator!=(std::nullptr_t) const noexcept
507  {
508  return m_handle != nullptr;
509  }
510 
513  explicit operator bool() const noexcept
514  {
515  return is_valid();
516  }
517 
520  bool is_valid() const noexcept
521  {
522  return m_handle != nullptr;
523  }
524 
532  k4a_capture_t handle() const noexcept
533  {
534  return m_handle;
535  }
536 
539  void reset() noexcept
540  {
541  if (m_handle != nullptr)
542  {
543  k4a_capture_release(m_handle);
544  m_handle = nullptr;
545  }
546  }
547 
552  image get_color_image() const noexcept
553  {
554  return image(k4a_capture_get_color_image(m_handle));
555  }
556 
561  image get_depth_image() const noexcept
562  {
563  return image(k4a_capture_get_depth_image(m_handle));
564  }
565 
570  image get_ir_image() const noexcept
571  {
572  return image(k4a_capture_get_ir_image(m_handle));
573  }
574 
579  void set_color_image(const image &color_image) noexcept
580  {
581  k4a_capture_set_color_image(m_handle, color_image.handle());
582  }
583 
588  void set_depth_image(const image &depth_image) noexcept
589  {
590  k4a_capture_set_depth_image(m_handle, depth_image.handle());
591  }
592 
597  void set_ir_image(const image &ir_image) noexcept
598  {
599  k4a_capture_set_ir_image(m_handle, ir_image.handle());
600  }
601 
606  void set_temperature_c(float temperature_c) noexcept
607  {
608  k4a_capture_set_temperature_c(m_handle, temperature_c);
609  }
610 
615  float get_temperature_c() const noexcept
616  {
617  return k4a_capture_get_temperature_c(m_handle);
618  }
619 
625  static capture create()
626  {
627  k4a_capture_t handle = nullptr;
628  k4a_result_t result = k4a_capture_create(&handle);
629  if (K4A_RESULT_SUCCEEDED != result)
630  {
631  throw error("Failed to create capture!");
632  }
633  return capture(handle);
634  }
635 
636 private:
637  k4a_capture_t m_handle;
638 };
639 
646 {
653  k4a_calibration_type_t source_camera,
654  k4a_calibration_type_t target_camera) const
655  {
656  k4a_float3_t target_point3d;
657  k4a_result_t result =
658  k4a_calibration_3d_to_3d(this, &source_point3d, source_camera, target_camera, &target_point3d);
659 
660  if (K4A_RESULT_SUCCEEDED != result)
661  {
662  throw error("Calibration contained invalid transformation parameters!");
663  }
664  return target_point3d;
665  }
666 
675  bool convert_2d_to_3d(const k4a_float2_t &source_point2d,
676  float source_depth,
677  k4a_calibration_type_t source_camera,
678  k4a_calibration_type_t target_camera,
679  k4a_float3_t *target_point3d) const
680  {
681  int valid = 0;
683  this, &source_point2d, source_depth, source_camera, target_camera, target_point3d, &valid);
684 
685  if (K4A_RESULT_SUCCEEDED != result)
686  {
687  throw error("Calibration contained invalid transformation parameters!");
688  }
689  return static_cast<bool>(valid);
690  }
691 
699  bool convert_3d_to_2d(const k4a_float3_t &source_point3d,
700  k4a_calibration_type_t source_camera,
701  k4a_calibration_type_t target_camera,
702  k4a_float2_t *target_point2d) const
703  {
704  int valid = 0;
705  k4a_result_t result =
706  k4a_calibration_3d_to_2d(this, &source_point3d, source_camera, target_camera, target_point2d, &valid);
707 
708  if (K4A_RESULT_SUCCEEDED != result)
709  {
710  throw error("Calibration contained invalid transformation parameters!");
711  }
712  return static_cast<bool>(valid);
713  }
714 
723  bool convert_2d_to_2d(const k4a_float2_t &source_point2d,
724  float source_depth,
725  k4a_calibration_type_t source_camera,
726  k4a_calibration_type_t target_camera,
727  k4a_float2_t *target_point2d) const
728  {
729  int valid = 0;
731  this, &source_point2d, source_depth, source_camera, target_camera, target_point2d, &valid);
732 
733  if (K4A_RESULT_SUCCEEDED != result)
734  {
735  throw error("Calibration contained invalid transformation parameters!");
736  }
737  return static_cast<bool>(valid);
738  }
739 
747  bool convert_color_2d_to_depth_2d(const k4a_float2_t &source_point2d,
748  const image &depth_image,
749  k4a_float2_t *target_point2d) const
750  {
751  int valid = 0;
752  k4a_result_t result =
753  k4a_calibration_color_2d_to_depth_2d(this, &source_point2d, depth_image.handle(), target_point2d, &valid);
754 
755  if (K4A_RESULT_SUCCEEDED != result)
756  {
757  throw error("Calibration contained invalid transformation parameters!");
758  }
759  return static_cast<bool>(valid);
760  }
761 
767  static calibration get_from_raw(char *raw_calibration,
768  size_t raw_calibration_size,
769  k4a_depth_mode_t target_depth_mode,
770  k4a_color_resolution_t target_color_resolution)
771  {
772  calibration calib;
773  k4a_result_t result = k4a_calibration_get_from_raw(raw_calibration,
774  raw_calibration_size,
775  target_depth_mode,
776  target_color_resolution,
777  &calib);
778 
779  if (K4A_RESULT_SUCCEEDED != result)
780  {
781  throw error("Failed to load calibration from raw calibration blob!");
782  }
783  return calib;
784  }
785 
791  static calibration get_from_raw(uint8_t *raw_calibration,
792  size_t raw_calibration_size,
793  k4a_depth_mode_t target_depth_mode,
794  k4a_color_resolution_t target_color_resolution)
795  {
796  return get_from_raw(reinterpret_cast<char *>(raw_calibration),
797  raw_calibration_size,
798  target_depth_mode,
799  target_color_resolution);
800  }
801 
807  static calibration get_from_raw(std::vector<uint8_t> &raw_calibration,
808  k4a_depth_mode_t target_depth_mode,
809  k4a_color_resolution_t target_color_resolution)
810  {
811  return get_from_raw(reinterpret_cast<char *>(raw_calibration.data()),
812  raw_calibration.size(),
813  target_depth_mode,
814  target_color_resolution);
815  }
816 };
817 
824 {
825 public:
831  m_handle(k4a_transformation_create(&calibration)),
836  {
837  }
838 
844  transformation(k4a_transformation_t handle = nullptr) noexcept : m_handle(handle) {}
845 
848  transformation(transformation &&other) noexcept :
849  m_handle(other.m_handle),
850  m_color_resolution(other.m_color_resolution),
851  m_depth_resolution(other.m_depth_resolution)
852  {
853  other.m_handle = nullptr;
854  }
855 
856  transformation(const transformation &) = delete;
857 
858  ~transformation()
859  {
860  destroy();
861  }
862 
866  {
867  if (this != &other)
868  {
869  destroy();
870  m_handle = other.m_handle;
871  m_color_resolution = other.m_color_resolution;
872  m_depth_resolution = other.m_depth_resolution;
873  other.m_handle = nullptr;
874  }
875 
876  return *this;
877  }
878 
881  transformation &operator=(std::nullptr_t) noexcept
882  {
883  destroy();
884  return *this;
885  }
886 
887  transformation &operator=(const transformation &) = delete;
888 
891  void destroy() noexcept
892  {
893  if (m_handle != nullptr)
894  {
895  k4a_transformation_destroy(m_handle);
896  m_handle = nullptr;
897  }
898  }
899 
906  void depth_image_to_color_camera(const image &depth_image, image *transformed_depth_image) const
907  {
908  k4a_result_t result = k4a_transformation_depth_image_to_color_camera(m_handle,
909  depth_image.handle(),
910  transformed_depth_image->handle());
911  if (K4A_RESULT_SUCCEEDED != result)
912  {
913  throw error("Failed to convert depth map to color camera geometry!");
914  }
915  }
916 
923  image depth_image_to_color_camera(const image &depth_image) const
924  {
925  image transformed_depth_image = image::create(K4A_IMAGE_FORMAT_DEPTH16,
926  m_color_resolution.width,
927  m_color_resolution.height,
928  m_color_resolution.width *
929  static_cast<int32_t>(sizeof(uint16_t)));
930  depth_image_to_color_camera(depth_image, &transformed_depth_image);
931  return transformed_depth_image;
932  }
933 
940  void depth_image_to_color_camera_custom(const image &depth_image,
941  const image &custom_image,
942  image *transformed_depth_image,
943  image *transformed_custom_image,
944  k4a_transformation_interpolation_type_t interpolation_type,
945  uint32_t invalid_custom_value) const
946  {
947  k4a_result_t result = k4a_transformation_depth_image_to_color_camera_custom(m_handle,
948  depth_image.handle(),
949  custom_image.handle(),
950  transformed_depth_image->handle(),
951  transformed_custom_image->handle(),
952  interpolation_type,
953  invalid_custom_value);
954  if (K4A_RESULT_SUCCEEDED != result)
955  {
956  throw error("Failed to convert depth map and custom image to color camera geometry!");
957  }
958  }
959 
966  std::pair<image, image>
968  const image &custom_image,
969  k4a_transformation_interpolation_type_t interpolation_type,
970  uint32_t invalid_custom_value) const
971  {
972  image transformed_depth_image = image::create(K4A_IMAGE_FORMAT_DEPTH16,
973  m_color_resolution.width,
974  m_color_resolution.height,
975  m_color_resolution.width *
976  static_cast<int32_t>(sizeof(uint16_t)));
977  int32_t bytes_per_pixel;
978  switch (custom_image.get_format())
979  {
981  bytes_per_pixel = static_cast<int32_t>(sizeof(int8_t));
982  break;
984  bytes_per_pixel = static_cast<int32_t>(sizeof(int16_t));
985  break;
986  default:
987  throw error("Failed to support this format of custom image!");
988  }
989  image transformed_custom_image = image::create(custom_image.get_format(),
990  m_color_resolution.width,
991  m_color_resolution.height,
992  m_color_resolution.width * bytes_per_pixel);
994  custom_image,
995  &transformed_depth_image,
996  &transformed_custom_image,
997  interpolation_type,
998  invalid_custom_value);
999  return { std::move(transformed_depth_image), std::move(transformed_custom_image) };
1000  }
1001 
1008  void color_image_to_depth_camera(const image &depth_image,
1009  const image &color_image,
1010  image *transformed_color_image) const
1011  {
1012  k4a_result_t result = k4a_transformation_color_image_to_depth_camera(m_handle,
1013  depth_image.handle(),
1014  color_image.handle(),
1015  transformed_color_image->handle());
1016  if (K4A_RESULT_SUCCEEDED != result)
1017  {
1018  throw error("Failed to convert color image to depth camera geometry!");
1019  }
1020  }
1021 
1028  image color_image_to_depth_camera(const image &depth_image, const image &color_image) const
1029  {
1030  image transformed_color_image = image::create(K4A_IMAGE_FORMAT_COLOR_BGRA32,
1031  m_depth_resolution.width,
1032  m_depth_resolution.height,
1033  m_depth_resolution.width * 4 *
1034  static_cast<int32_t>(sizeof(uint8_t)));
1035  color_image_to_depth_camera(depth_image, color_image, &transformed_color_image);
1036  return transformed_color_image;
1037  }
1038 
1045  void depth_image_to_point_cloud(const image &depth_image, k4a_calibration_type_t camera, image *xyz_image) const
1046  {
1047  k4a_result_t result =
1048  k4a_transformation_depth_image_to_point_cloud(m_handle, depth_image.handle(), camera, xyz_image->handle());
1049  if (K4A_RESULT_SUCCEEDED != result)
1050  {
1051  throw error("Failed to transform depth image to point cloud!");
1052  }
1053  }
1054 
1062  {
1064  depth_image.get_width_pixels(),
1065  depth_image.get_height_pixels(),
1066  depth_image.get_width_pixels() * 3 * static_cast<int32_t>(sizeof(int16_t)));
1067  depth_image_to_point_cloud(depth_image, camera, &xyz_image);
1068  return xyz_image;
1069  }
1070 
1071 private:
1072  k4a_transformation_t m_handle;
1073  struct resolution
1074  {
1075  int32_t width;
1076  int32_t height;
1077  };
1078  resolution m_color_resolution;
1079  resolution m_depth_resolution;
1080 };
1081 
1087 class device
1088 {
1089 public:
1095  device(k4a_device_t handle = nullptr) noexcept : m_handle(handle) {}
1096 
1099  device(device &&dev) noexcept : m_handle(dev.m_handle)
1100  {
1101  dev.m_handle = nullptr;
1102  }
1103 
1104  device(const device &) = delete;
1105 
1106  ~device()
1107  {
1108  close();
1109  }
1110 
1111  device &operator=(const device &) = delete;
1112 
1115  device &operator=(device &&dev) noexcept
1116  {
1117  if (this != &dev)
1118  {
1119  close();
1120  m_handle = dev.m_handle;
1121  dev.m_handle = nullptr;
1122  }
1123  return *this;
1124  }
1125 
1128  explicit operator bool() const noexcept
1129  {
1130  return is_valid();
1131  }
1132 
1135  bool is_valid() const noexcept
1136  {
1137  return m_handle != nullptr;
1138  }
1139 
1145  k4a_device_t handle() const noexcept
1146  {
1147  return m_handle;
1148  }
1149 
1154  void close() noexcept
1155  {
1156  if (m_handle != nullptr)
1157  {
1158  k4a_device_close(m_handle);
1159  m_handle = nullptr;
1160  }
1161  }
1162 
1168  bool get_capture(capture *cap, std::chrono::milliseconds timeout)
1169  {
1170  k4a_capture_t capture_handle = nullptr;
1171  int32_t timeout_ms = internal::clamp_cast<int32_t>(timeout.count());
1172  k4a_wait_result_t result = k4a_device_get_capture(m_handle, &capture_handle, timeout_ms);
1173  if (result == K4A_WAIT_RESULT_FAILED)
1174  {
1175  throw error("Failed to get capture from device!");
1176  }
1177  else if (result == K4A_WAIT_RESULT_TIMEOUT)
1178  {
1179  return false;
1180  }
1181 
1182  *cap = capture(capture_handle);
1183  return true;
1184  }
1185 
1192  {
1193  return get_capture(cap, std::chrono::milliseconds(K4A_WAIT_INFINITE));
1194  }
1195 
1201  bool get_imu_sample(k4a_imu_sample_t *imu_sample, std::chrono::milliseconds timeout)
1202  {
1203  int32_t timeout_ms = internal::clamp_cast<int32_t>(timeout.count());
1204  k4a_wait_result_t result = k4a_device_get_imu_sample(m_handle, imu_sample, timeout_ms);
1205  if (result == K4A_WAIT_RESULT_FAILED)
1206  {
1207  throw error("Failed to get IMU sample from device!");
1208  }
1209  else if (result == K4A_WAIT_RESULT_TIMEOUT)
1210  {
1211  return false;
1212  }
1213 
1214  return true;
1215  }
1216 
1223  {
1224  return get_imu_sample(imu_sample, std::chrono::milliseconds(K4A_WAIT_INFINITE));
1225  }
1226 
1232  void start_cameras(const k4a_device_configuration_t *configuration)
1233  {
1234  k4a_result_t result = k4a_device_start_cameras(m_handle, configuration);
1235  if (K4A_RESULT_SUCCEEDED != result)
1236  {
1237  throw error("Failed to start cameras!");
1238  }
1239  }
1240 
1245  void stop_cameras() noexcept
1246  {
1247  k4a_device_stop_cameras(m_handle);
1248  }
1249 
1255  void start_imu()
1256  {
1257  k4a_result_t result = k4a_device_start_imu(m_handle);
1258  if (K4A_RESULT_SUCCEEDED != result)
1259  {
1260  throw error("Failed to start IMU!");
1261  }
1262  }
1263 
1268  void stop_imu() noexcept
1269  {
1270  k4a_device_stop_imu(m_handle);
1271  }
1272 
1278  std::string get_serialnum() const
1279  {
1280  std::string serialnum;
1281  size_t buffer = 0;
1282  k4a_buffer_result_t result = k4a_device_get_serialnum(m_handle, &serialnum[0], &buffer);
1283 
1284  if (result == K4A_BUFFER_RESULT_TOO_SMALL && buffer > 1)
1285  {
1286  serialnum.resize(buffer);
1287  result = k4a_device_get_serialnum(m_handle, &serialnum[0], &buffer);
1288  if (result == K4A_BUFFER_RESULT_SUCCEEDED && serialnum[buffer - 1] == 0)
1289  {
1290  // std::string expects there to not be as null terminator at the end of its data but
1291  // k4a_device_get_serialnum adds a null terminator, so we drop the last character of the string after we
1292  // get the result back.
1293  serialnum.resize(buffer - 1);
1294  }
1295  }
1296 
1297  if (result != K4A_BUFFER_RESULT_SUCCEEDED)
1298  {
1299  throw error("Failed to read device serial number!");
1300  }
1301 
1302  return serialnum;
1303  }
1304 
1311  {
1312  k4a_result_t result = k4a_device_get_color_control(m_handle, command, mode, value);
1313  if (K4A_RESULT_SUCCEEDED != result)
1314  {
1315  throw error("Failed to read color control!");
1316  }
1317  }
1318 
1325  {
1326  k4a_result_t result = k4a_device_set_color_control(m_handle, command, mode, value);
1327  if (K4A_RESULT_SUCCEEDED != result)
1328  {
1329  throw error("Failed to set color control!");
1330  }
1331  }
1332 
1338  std::vector<uint8_t> get_raw_calibration() const
1339  {
1340  std::vector<uint8_t> calibration;
1341  size_t buffer = 0;
1342  k4a_buffer_result_t result = k4a_device_get_raw_calibration(m_handle, nullptr, &buffer);
1343 
1344  if (result == K4A_BUFFER_RESULT_TOO_SMALL && buffer > 1)
1345  {
1346  calibration.resize(buffer);
1347  result = k4a_device_get_raw_calibration(m_handle, &calibration[0], &buffer);
1348  }
1349 
1350  if (result != K4A_BUFFER_RESULT_SUCCEEDED)
1351  {
1352  throw error("Failed to read raw device calibration!");
1353  }
1354 
1355  return calibration;
1356  }
1357 
1364  {
1365  calibration calib;
1366  k4a_result_t result = k4a_device_get_calibration(m_handle, depth_mode, color_resolution, &calib);
1367 
1368  if (K4A_RESULT_SUCCEEDED != result)
1369  {
1370  throw error("Failed to read device calibration!");
1371  }
1372  return calib;
1373  }
1374 
1381  {
1382  bool sync_in_jack_connected, sync_out_jack_connected;
1383  k4a_result_t result = k4a_device_get_sync_jack(m_handle, &sync_in_jack_connected, &sync_out_jack_connected);
1384 
1385  if (K4A_RESULT_SUCCEEDED != result)
1386  {
1387  throw error("Failed to read sync jack status!");
1388  }
1389  return sync_in_jack_connected;
1390  }
1391 
1398  {
1399  bool sync_in_jack_connected, sync_out_jack_connected;
1400  k4a_result_t result = k4a_device_get_sync_jack(m_handle, &sync_in_jack_connected, &sync_out_jack_connected);
1401 
1402  if (K4A_RESULT_SUCCEEDED != result)
1403  {
1404  throw error("Failed to read sync jack status!");
1405  }
1406  return sync_out_jack_connected;
1407  }
1408 
1415  {
1416  k4a_hardware_version_t version;
1417  k4a_result_t result = k4a_device_get_version(m_handle, &version);
1418 
1419  if (K4A_RESULT_SUCCEEDED != result)
1420  {
1421  throw error("Failed to read device firmware information!");
1422  }
1423  return version;
1424  }
1425 
1431  static device open(uint32_t index)
1432  {
1433  k4a_device_t handle = nullptr;
1434  k4a_result_t result = k4a_device_open(index, &handle);
1435 
1436  if (K4A_RESULT_SUCCEEDED != result)
1437  {
1438  throw error("Failed to open device!");
1439  }
1440  return device(handle);
1441  }
1442 
1447  static uint32_t get_installed_count() noexcept
1448  {
1449  return k4a_device_get_installed_count();
1450  }
1451 
1452 private:
1453  k4a_device_t m_handle;
1454 };
1455 
1460 } // namespace k4a
1461 
1462 #endif
bool is_sync_out_connected() const
Get the device jack status for the synchronization out connector Throws error on failure.
Definition: k4a.hpp:1397
Calibration type representing device calibration.
Definition: k4atypes.h:1099
The result was successful.
Definition: k4atypes.h:233
transformation(const k4a_calibration_t &calibration) noexcept
Creates a transformation associated with calibration.
Definition: k4a.hpp:830
void reset() noexcept
Releases the underlying k4a_image_t; the image is set to invalid.
Definition: k4a.hpp:205
k4a_float3_t convert_3d_to_3d(const k4a_float3_t &source_point3d, k4a_calibration_type_t source_camera, k4a_calibration_type_t target_camera) const
Transform a 3d point of a source coordinate system into a 3d point of the target coordinate system...
Definition: k4a.hpp:652
capture & operator=(capture &&other) noexcept
Moves another capture into this capture; other is set to invalid.
Definition: k4a.hpp:464
transformation(transformation &&other) noexcept
Moves another tranformation into a new transformation.
Definition: k4a.hpp:848
void set_exposure_time(std::chrono::microseconds exposure) noexcept
Set the image&#39;s exposure time in microseconds (color images only)
Definition: k4a.hpp:382
int resolution_height
Resolution height of the calibration sensor.
Definition: k4atypes.h:1087
Color image type BGRA32.
Definition: k4atypes.h:386
k4a_result_t k4a_calibration_color_2d_to_depth_2d(const k4a_calibration_t *calibration, const k4a_float2_t *source_point2d, const k4a_image_t depth_image, k4a_float2_t *target_point2d, int *valid)
Transform a 2D pixel coordinate from color camera into a 2D pixel coordinate of the depth camera...
const uint8_t * get_buffer() const noexcept
Get the image buffer.
Definition: k4a.hpp:274
Structure to define hardware version.
Definition: k4atypes.h:1141
image depth_image_to_color_camera(const image &depth_image) const
Transforms the depth map into the geometry of the color camera.
Definition: k4a.hpp:923
int get_stride_bytes() const noexcept
Get the image stride in bytes.
Definition: k4a.hpp:319
k4a_result_t
Result code returned by Azure Kinect APIs.
Definition: k4atypes.h:217
static calibration get_from_raw(char *raw_calibration, size_t raw_calibration_size, k4a_depth_mode_t target_depth_mode, k4a_color_resolution_t target_color_resolution)
Get the camera calibration for a device from a raw calibration blob.
Definition: k4a.hpp:767
Exception type thrown when a K4A API call fails.
Definition: k4a.hpp:33
void set_color_image(const image &color_image) noexcept
Set / add a color image to the capture.
Definition: k4a.hpp:579
void set_depth_image(const image &depth_image) noexcept
Set / add a depth image to the capture.
Definition: k4a.hpp:588
size_t get_size() const noexcept
Get the image buffer size in bytes.
Definition: k4a.hpp:283
k4a_depth_mode_t
Depth sensor capture modes.
Definition: k4atypes.h:290
Handle to an Azure Kinect capture.
Definition: k4atypes.h:122
bool operator==(std::nullptr_t) const noexcept
Returns false if the capture is valid, true otherwise.
Definition: k4a.hpp:492
static calibration get_from_raw(uint8_t *raw_calibration, size_t raw_calibration_size, k4a_depth_mode_t target_depth_mode, k4a_color_resolution_t target_color_resolution)
Get the camera calibration for a device from a raw calibration blob.
Definition: k4a.hpp:791
uint32_t get_white_balance() const noexcept
Get the image white balance in Kelvin (color images only)
Definition: k4a.hpp:355
k4a_buffer_result_t
Result code returned by Azure Kinect APIs.
Definition: k4atypes.h:231
static device open(uint32_t index)
Open a k4a device.
Definition: k4a.hpp:1431
capture & operator=(const capture &other) noexcept
Sets capture to a shallow copy of the other image.
Definition: k4a.hpp:448
bool get_imu_sample(k4a_imu_sample_t *imu_sample)
Reads an IMU sample.
Definition: k4a.hpp:1222
void depth_image_to_color_camera(const image &depth_image, image *transformed_depth_image) const
Transforms the depth map into the geometry of the color camera.
Definition: k4a.hpp:906
Wrapper for k4a_transformation_t.
Definition: k4a.hpp:823
The operation timed out.
Definition: k4atypes.h:250
bool get_capture(capture *cap)
Reads a sensor capture into cap.
Definition: k4a.hpp:1191
image(k4a_image_t handle=nullptr) noexcept
Creates an image from a k4a_image_t.
Definition: k4a.hpp:88
device & operator=(device &&dev) noexcept
Moves another device into this device; other is set to invalid.
Definition: k4a.hpp:1115
std::vector< uint8_t > get_raw_calibration() const
Get the raw calibration blob for the entire K4A device.
Definition: k4a.hpp:1338
int get_width_pixels() const noexcept
Get the image width in pixels.
Definition: k4a.hpp:301
IMU sample.
Definition: k4atypes.h:1199
std::chrono::microseconds get_exposure() const noexcept
Get the image exposure time in microseconds.
Definition: k4a.hpp:346
bool is_valid() const noexcept
Returns true if the capture is valid, false otherwise.
Definition: k4a.hpp:520
void start_cameras(const k4a_device_configuration_t *configuration)
Starts the K4A device&#39;s cameras Throws error on failure.
Definition: k4a.hpp:1232
bool operator!=(const capture &other) const noexcept
Returns true if two captures wrap different k4a_capture_t instances, false otherwise.
Definition: k4a.hpp:499
bool convert_2d_to_2d(const k4a_float2_t &source_point2d, float source_depth, k4a_calibration_type_t source_camera, k4a_calibration_type_t target_camera, k4a_float2_t *target_point2d) const
Transform a 2d pixel coordinate with an associated depth value of the source camera into a 2d pixel c...
Definition: k4a.hpp:723
k4a_transformation_interpolation_type_t
Transformation interpolation type.
Definition: k4atypes.h:459
transformation & operator=(std::nullptr_t) noexcept
Invalidates this transformation.
Definition: k4a.hpp:881
Definition: k4a.hpp:20
std::chrono::microseconds get_device_timestamp() const noexcept
Get the image&#39;s device timestamp in microseconds.
Definition: k4a.hpp:328
k4a_result_t k4a_calibration_3d_to_2d(const k4a_calibration_t *calibration, const k4a_float3_t *source_point3d_mm, const k4a_calibration_type_t source_camera, const k4a_calibration_type_t target_camera, k4a_float2_t *target_point2d, int *valid)
Transform a 3D point of a source coordinate system into a 2D pixel coordinate of the target camera...
calibration get_calibration(k4a_depth_mode_t depth_mode, k4a_color_resolution_t color_resolution) const
Get the camera calibration for the entire K4A device, which is used for all transformation functions...
Definition: k4a.hpp:1363
void set_iso_speed(uint32_t iso_speed) noexcept
Set the ISO speed of the image (color images only)
Definition: k4a.hpp:400
void set_ir_image(const image &ir_image) noexcept
Set / add an IR image to the capture.
Definition: k4a.hpp:597
image & operator=(const image &other) noexcept
Sets image to a shallow copy of the other image.
Definition: k4a.hpp:114
bool get_imu_sample(k4a_imu_sample_t *imu_sample, std::chrono::milliseconds timeout)
Reads an IMU sample.
Definition: k4a.hpp:1201
capture(capture &&other) noexcept
Moves another capture into a new capture.
Definition: k4a.hpp:436
std::chrono::nanoseconds get_system_timestamp() const noexcept
Get the image&#39;s system timestamp in nanoseconds.
Definition: k4a.hpp:337
bool is_sync_in_connected() const
Get the device jack status for the synchronization in connector Throws error on failure.
Definition: k4a.hpp:1380
Single channel image type CUSTOM16.
Definition: k4atypes.h:435
k4a_calibration_type_t
Calibration types.
Definition: k4atypes.h:658
image get_color_image() const noexcept
Get the color image associated with the capture.
Definition: k4a.hpp:552
static uint32_t get_installed_count() noexcept
Gets the number of connected devices.
Definition: k4a.hpp:1447
bool operator!=(std::nullptr_t) const noexcept
Returns true if the capture is valid, false otherwise.
Definition: k4a.hpp:506
void get_color_control(k4a_color_control_command_t command, k4a_color_control_mode_t *mode, int32_t *value) const
Get the K4A color sensor control value Throws error on failure.
Definition: k4a.hpp:1310
static image create_from_buffer(k4a_image_format_t format, int width_pixels, int height_pixels, int stride_bytes, uint8_t *buffer, size_t buffer_size, k4a_memory_destroy_cb_t *buffer_release_cb, void *buffer_release_cb_context)
Create an image from a pre-allocated buffer Throws error on failure.
Definition: k4a.hpp:235
k4a_result_t k4a_calibration_2d_to_2d(const k4a_calibration_t *calibration, const k4a_float2_t *source_point2d, const float source_depth_mm, const k4a_calibration_type_t source_camera, const k4a_calibration_type_t target_camera, k4a_float2_t *target_point2d, int *valid)
Transform a 2D pixel coordinate with an associated depth value of the source camera into a 2D pixel c...
void set_timestamp(std::chrono::microseconds timestamp) noexcept
Set the image&#39;s timestamp in microseconds.
Definition: k4a.hpp:373
bool convert_3d_to_2d(const k4a_float3_t &source_point3d, k4a_calibration_type_t source_camera, k4a_calibration_type_t target_camera, k4a_float2_t *target_point2d) const
Transform a 3d point of a source coordinate system into a 2d pixel coordinate of the target camera...
Definition: k4a.hpp:699
Wrapper for k4a_capture_t.
Definition: k4a.hpp:414
void depth_image_to_color_camera_custom(const image &depth_image, const image &custom_image, image *transformed_depth_image, image *transformed_custom_image, k4a_transformation_interpolation_type_t interpolation_type, uint32_t invalid_custom_value) const
Transforms depth map and a custom image into the geometry of the color camera.
Definition: k4a.hpp:940
k4a_result_t k4a_calibration_3d_to_3d(const k4a_calibration_t *calibration, const k4a_float3_t *source_point3d_mm, const k4a_calibration_type_t source_camera, const k4a_calibration_type_t target_camera, k4a_float3_t *target_point3d_mm)
Transform a 3D point of a source coordinate system into a 3D point of the target coordinate system...
Three dimensional floating point vector.
Definition: k4atypes.h:1179
bool is_valid() const noexcept
Returns true if the device is valid, false otherwise.
Definition: k4a.hpp:1135
bool operator!=(std::nullptr_t) const noexcept
Returns true if the image is valid, false otherwise.
Definition: k4a.hpp:172
capture(k4a_capture_t handle=nullptr) noexcept
Creates a capture from a k4a_capture_t Takes ownership of the handle, i.e.
Definition: k4a.hpp:422
k4a_device_t handle() const noexcept
Returns the underlying k4a_device_t handle.
Definition: k4a.hpp:1145
static capture create()
Create an empty capture object.
Definition: k4a.hpp:625
transformation(k4a_transformation_t handle=nullptr) noexcept
Creates a transformation from a k4a_transformation_t Takes ownership of the handle, i.e.
Definition: k4a.hpp:844
k4a_color_control_mode_t
Color sensor control mode.
Definition: k4atypes.h:622
Single channel image type CUSTOM8.
Definition: k4atypes.h:424
std::string get_serialnum() const
Get the K4A device serial number Throws error on failure.
Definition: k4a.hpp:1278
bool operator!=(const image &other) const noexcept
Returns true if two images wrap different k4a_image_t instances, false otherwise. ...
Definition: k4a.hpp:165
bool is_valid() const noexcept
Returns true if the image is valid, false otherwise.
Definition: k4a.hpp:186
capture(const capture &other) noexcept
Creates a shallow copy of another capture.
Definition: k4a.hpp:426
k4a_image_t handle() const noexcept
Returns the underlying k4a_image_t handle.
Definition: k4a.hpp:198
k4a_image_format_t get_format() const noexcept
Get the image format of the image.
Definition: k4a.hpp:292
std::pair< image, image > depth_image_to_color_camera_custom(const image &depth_image, const image &custom_image, k4a_transformation_interpolation_type_t interpolation_type, uint32_t invalid_custom_value) const
Transforms depth map and a custom image into the geometry of the color camera.
Definition: k4a.hpp:967
int get_height_pixels() const noexcept
Get the image height in pixels.
Definition: k4a.hpp:310
Handle to an Azure Kinect transformation context.
Definition: k4atypes.h:195
image color_image_to_depth_camera(const image &depth_image, const image &color_image) const
Transforms the color image into the geometry of the depth camera.
Definition: k4a.hpp:1028
Depth image type DEPTH16.
Definition: k4atypes.h:398
k4a_color_resolution_t
Color sensor resolutions.
Definition: k4atypes.h:309
float get_temperature_c() const noexcept
Get temperature (in Celsius) associated with the capture.
Definition: k4a.hpp:615
void() k4a_memory_destroy_cb_t(void *buffer, void *context)
Callback function for a memory object being destroyed.
Definition: k4atypes.h:868
void set_white_balance(uint32_t white_balance) noexcept
Set the white balance of the image (color images only)
Definition: k4a.hpp:391
k4a_result_t k4a_calibration_2d_to_3d(const k4a_calibration_t *calibration, const k4a_float2_t *source_point2d, const float source_depth_mm, const k4a_calibration_type_t source_camera, const k4a_calibration_type_t target_camera, k4a_float3_t *target_point3d_mm, int *valid)
Transform a 2D pixel coordinate with an associated depth value of the source camera into a 3D point o...
#define K4A_WAIT_INFINITE
An infinite wait time for functions that take a timeout parameter.
Definition: k4atypes.h:1240
The result was successful.
Definition: k4atypes.h:219
device(k4a_device_t handle=nullptr) noexcept
Creates a device from a k4a_device_t Takes ownership of the handle, i.e.
Definition: k4a.hpp:1095
void destroy() noexcept
Invalidates this transformation.
Definition: k4a.hpp:891
void stop_imu() noexcept
Stops the K4A IMU.
Definition: k4a.hpp:1268
uint32_t get_iso_speed() const noexcept
Get the image&#39;s ISO speed (color images only)
Definition: k4a.hpp:364
k4a_calibration_camera_t color_camera_calibration
Color camera calibration.
Definition: k4atypes.h:1103
image & operator=(image &&other) noexcept
Moves another image into this image; other is set to invalid.
Definition: k4a.hpp:130
Wrapper for k4a_image_t.
Definition: k4a.hpp:80
void set_temperature_c(float temperature_c) noexcept
Set the temperature associated with the capture in Celsius.
Definition: k4a.hpp:606
image get_ir_image() const noexcept
Get the IR image associated with the capture.
Definition: k4a.hpp:570
bool convert_2d_to_3d(const k4a_float2_t &source_point2d, float source_depth, k4a_calibration_type_t source_camera, k4a_calibration_type_t target_camera, k4a_float3_t *target_point3d) const
Transform a 2d pixel coordinate with an associated depth value of the source camera into a 3d point o...
Definition: k4a.hpp:675
k4a_capture_t handle() const noexcept
Returns the underlying k4a_capture_t handle.
Definition: k4a.hpp:532
device(device &&dev) noexcept
Moves another device into a new device.
Definition: k4a.hpp:1099
int resolution_width
Resolution width of the calibration sensor.
Definition: k4atypes.h:1086
image & operator=(std::nullptr_t) noexcept
Invalidates this image.
Definition: k4a.hpp:143
k4a_calibration_camera_t depth_camera_calibration
Depth camera calibration.
Definition: k4atypes.h:1101
Handle to an Azure Kinect device.
Definition: k4atypes.h:66
uint8_t * get_buffer() noexcept
Get the image buffer.
Definition: k4a.hpp:265
void color_image_to_depth_camera(const image &depth_image, const image &color_image, image *transformed_color_image) const
Transforms the color image into the geometry of the depth camera.
Definition: k4a.hpp:1008
Two dimensional floating point vector.
Definition: k4atypes.h:1160
bool operator==(std::nullptr_t) const noexcept
Returns false if the image is valid, true otherwise.
Definition: k4a.hpp:158
Handle to an Azure Kinect image.
Definition: k4atypes.h:173
image(image &&other) noexcept
Moves another image into a new image.
Definition: k4a.hpp:102
image(const image &other) noexcept
Creates a shallow copy of another image.
Definition: k4a.hpp:92
bool get_capture(capture *cap, std::chrono::milliseconds timeout)
Reads a sensor capture into cap.
Definition: k4a.hpp:1168
Wrapper for k4a_device_t.
Definition: k4a.hpp:1087
void depth_image_to_point_cloud(const image &depth_image, k4a_calibration_type_t camera, image *xyz_image) const
Transforms the depth image into 3 planar images representing X, Y and Z-coordinates of corresponding ...
Definition: k4a.hpp:1045
Configuration parameters for an Azure Kinect device.
Definition: k4atypes.h:917
The result was a failure.
Definition: k4atypes.h:249
void stop_cameras() noexcept
Stops the K4A device&#39;s cameras.
Definition: k4a.hpp:1245
The input buffer was too small.
Definition: k4atypes.h:235
capture & operator=(std::nullptr_t) noexcept
Invalidates this capture.
Definition: k4a.hpp:477
bool operator==(const capture &other) const noexcept
Returns true if two captures refer to the same k4a_capture_t, false otherwise.
Definition: k4a.hpp:485
void set_color_control(k4a_color_control_command_t command, k4a_color_control_mode_t mode, int32_t value)
Set the K4A color sensor control value Throws error on failure.
Definition: k4a.hpp:1324
bool operator==(const image &other) const noexcept
Returns true if two images refer to the same k4a_image_t, false otherwise.
Definition: k4a.hpp:151
k4a_color_control_command_t
Color sensor control commands.
Definition: k4atypes.h:503
Custom image format.
Definition: k4atypes.h:445
k4a_hardware_version_t get_version() const
Get the version numbers of the K4A subsystems&#39; firmware Throws error on failure.
Definition: k4a.hpp:1414
static image create(k4a_image_format_t format, int width_pixels, int height_pixels, int stride_bytes)
Create a blank image Throws error on failure.
Definition: k4a.hpp:219
bool convert_color_2d_to_depth_2d(const k4a_float2_t &source_point2d, const image &depth_image, k4a_float2_t *target_point2d) const
Transform a 2D pixel coordinate from color camera into a 2D pixel coordinate of the depth camera...
Definition: k4a.hpp:747
Wrapper for k4a_calibration_t.
Definition: k4a.hpp:645
void start_imu()
Starts the K4A IMU Throws error on failure.
Definition: k4a.hpp:1255
k4a_wait_result_t
Result code returned by Azure Kinect APIs.
Definition: k4atypes.h:246
transformation & operator=(transformation &&other) noexcept
Moves another image into this image; other is set to invalid.
Definition: k4a.hpp:865
k4a_image_format_t
Image format type.
Definition: k4atypes.h:332
void close() noexcept
Closes a k4a device.
Definition: k4a.hpp:1154
image depth_image_to_point_cloud(const image &depth_image, k4a_calibration_type_t camera) const
Transforms the depth image into 3 planar images representing X, Y and Z-coordinates of corresponding ...
Definition: k4a.hpp:1061
image get_depth_image() const noexcept
Get the depth image associated with the capture.
Definition: k4a.hpp:561
static calibration get_from_raw(std::vector< uint8_t > &raw_calibration, k4a_depth_mode_t target_depth_mode, k4a_color_resolution_t target_color_resolution)
Get the camera calibration for a device from a raw calibration blob.
Definition: k4a.hpp:807
void reset() noexcept
Releases the underlying k4a_capture_t; the capture is set to invalid.
Definition: k4a.hpp:539