Azure Kinect Sensor SDK  refs/pull/413/merge
Documentation for https://github.com/Microsoft/Azure-Kinect-Sensor-SDK
All Data Structures Functions Variables Typedefs Enumerations Enumerator Modules Pages
k4a.h
1 
7 #ifndef K4A_H
8 #define K4A_H
9 
10 #ifdef __cplusplus
11 #include <cinttypes>
12 #else
13 #include <inttypes.h>
14 #endif
15 #include <k4a/k4aversion.h>
16 #include <k4a/k4atypes.h>
17 #include <k4a/k4a_export.h>
18 
19 #ifdef __cplusplus
20 extern "C" {
21 #endif
22 
49 K4A_EXPORT uint32_t k4a_device_get_installed_count(void);
50 
96  void *message_cb_context,
97  k4a_log_level_t min_level);
98 
126 K4A_EXPORT k4a_result_t k4a_device_open(uint32_t index, k4a_device_t *device_handle);
127 
148 K4A_EXPORT void k4a_device_close(k4a_device_t device_handle);
149 
209 K4A_EXPORT k4a_wait_result_t k4a_device_get_capture(k4a_device_t device_handle,
210  k4a_capture_t *capture_handle,
211  int32_t timeout_in_ms);
212 
268  k4a_imu_sample_t *imu_sample,
269  int32_t timeout_in_ms);
270 
295 K4A_EXPORT k4a_result_t k4a_capture_create(k4a_capture_t *capture_handle);
296 
315 K4A_EXPORT void k4a_capture_release(k4a_capture_t capture_handle);
316 
336 K4A_EXPORT void k4a_capture_reference(k4a_capture_t capture_handle);
337 
357 K4A_EXPORT k4a_image_t k4a_capture_get_color_image(k4a_capture_t capture_handle);
358 
378 K4A_EXPORT k4a_image_t k4a_capture_get_depth_image(k4a_capture_t capture_handle);
379 
399 K4A_EXPORT k4a_image_t k4a_capture_get_ir_image(k4a_capture_t capture_handle);
400 
435 K4A_EXPORT void k4a_capture_set_color_image(k4a_capture_t capture_handle, k4a_image_t image_handle);
436 
471 K4A_EXPORT void k4a_capture_set_depth_image(k4a_capture_t capture_handle, k4a_image_t image_handle);
472 
506 K4A_EXPORT void k4a_capture_set_ir_image(k4a_capture_t capture_handle, k4a_image_t image_handle);
507 
526 K4A_EXPORT void k4a_capture_set_temperature_c(k4a_capture_t capture_handle, float temperature_c);
527 
547 K4A_EXPORT float k4a_capture_get_temperature_c(k4a_capture_t capture_handle);
548 
597  int width_pixels,
598  int height_pixels,
599  int stride_bytes,
600  k4a_image_t *image_handle);
601 
659  int width_pixels,
660  int height_pixels,
661  int stride_bytes,
662  uint8_t *buffer,
663  size_t buffer_size,
664  k4a_memory_destroy_cb_t *buffer_release_cb,
665  void *buffer_release_cb_context,
666  k4a_image_t *image_handle);
667 
691 K4A_EXPORT uint8_t *k4a_image_get_buffer(k4a_image_t image_handle);
692 
716 K4A_EXPORT size_t k4a_image_get_size(k4a_image_t image_handle);
717 
740 K4A_EXPORT k4a_image_format_t k4a_image_get_format(k4a_image_t image_handle);
741 
761 K4A_EXPORT int k4a_image_get_width_pixels(k4a_image_t image_handle);
762 
782 K4A_EXPORT int k4a_image_get_height_pixels(k4a_image_t image_handle);
783 
803 K4A_EXPORT int k4a_image_get_stride_bytes(k4a_image_t image_handle);
804 
832 K4A_DEPRECATED_EXPORT uint64_t k4a_image_get_timestamp_usec(k4a_image_t image_handle);
833 
858 K4A_EXPORT uint64_t k4a_image_get_device_timestamp_usec(k4a_image_t image_handle);
859 
893 K4A_EXPORT uint64_t k4a_image_get_system_timestamp_nsec(k4a_image_t image_handle);
894 
917 K4A_EXPORT uint64_t k4a_image_get_exposure_usec(k4a_image_t image_handle);
918 
941 K4A_EXPORT uint32_t k4a_image_get_white_balance(k4a_image_t image_handle);
942 
964 K4A_EXPORT uint32_t k4a_image_get_iso_speed(k4a_image_t image_handle);
965 
991 K4A_EXPORT void k4a_image_set_device_timestamp_usec(k4a_image_t image_handle, uint64_t timestamp_usec);
992 
1021 K4A_DEPRECATED_EXPORT void k4a_image_set_timestamp_usec(k4a_image_t image_handle, uint64_t timestamp_usec);
1022 
1049 K4A_EXPORT void k4a_image_set_system_timestamp_nsec(k4a_image_t image_handle, uint64_t timestamp_nsec);
1050 
1074 K4A_EXPORT void k4a_image_set_exposure_usec(k4a_image_t image_handle, uint64_t exposure_usec);
1075 
1102 K4A_DEPRECATED_EXPORT void k4a_image_set_exposure_time_usec(k4a_image_t image_handle, uint64_t exposure_usec);
1103 
1127 K4A_EXPORT void k4a_image_set_white_balance(k4a_image_t image_handle, uint32_t white_balance);
1128 
1151 K4A_EXPORT void k4a_image_set_iso_speed(k4a_image_t image_handle, uint32_t iso_speed);
1152 
1172 K4A_EXPORT void k4a_image_reference(k4a_image_t image_handle);
1173 
1193 K4A_EXPORT void k4a_image_release(k4a_image_t image_handle);
1194 
1223 K4A_EXPORT k4a_result_t k4a_device_start_cameras(k4a_device_t device_handle, const k4a_device_configuration_t *config);
1224 
1248 K4A_EXPORT void k4a_device_stop_cameras(k4a_device_t device_handle);
1249 
1277 K4A_EXPORT k4a_result_t k4a_device_start_imu(k4a_device_t device_handle);
1278 
1302 K4A_EXPORT void k4a_device_stop_imu(k4a_device_t device_handle);
1303 
1343  char *serial_number,
1344  size_t *serial_number_size);
1345 
1367 K4A_EXPORT k4a_result_t k4a_device_get_version(k4a_device_t device_handle, k4a_hardware_version_t *version);
1368 
1411  bool *supports_auto,
1412  int32_t *min_value,
1413  int32_t *max_value,
1414  int32_t *step_value,
1415  int32_t *default_value,
1416  k4a_color_control_mode_t *default_mode);
1417 
1460 K4A_EXPORT k4a_result_t k4a_device_get_color_control(k4a_device_t device_handle,
1463  int32_t *value);
1464 
1505 K4A_EXPORT k4a_result_t k4a_device_set_color_control(k4a_device_t device_handle,
1508  int32_t value);
1509 
1540  uint8_t *data,
1541  size_t *data_size);
1542 
1582 K4A_EXPORT k4a_result_t k4a_device_get_calibration(k4a_device_t device_handle,
1583  const k4a_depth_mode_t depth_mode,
1584  const k4a_color_resolution_t color_resolution,
1585  k4a_calibration_t *calibration);
1586 
1619 K4A_EXPORT k4a_result_t k4a_device_get_sync_jack(k4a_device_t device_handle,
1620  bool *sync_in_jack_connected,
1621  bool *sync_out_jack_connected);
1622 
1665 K4A_EXPORT k4a_result_t k4a_calibration_get_from_raw(char *raw_calibration,
1666  size_t raw_calibration_size,
1667  const k4a_depth_mode_t depth_mode,
1668  const k4a_color_resolution_t color_resolution,
1669  k4a_calibration_t *calibration);
1670 
1709 K4A_EXPORT k4a_result_t k4a_calibration_3d_to_3d(const k4a_calibration_t *calibration,
1710  const k4a_float3_t *source_point3d_mm,
1711  const k4a_calibration_type_t source_camera,
1712  const k4a_calibration_type_t target_camera,
1713  k4a_float3_t *target_point3d_mm);
1714 
1769 K4A_EXPORT k4a_result_t k4a_calibration_2d_to_3d(const k4a_calibration_t *calibration,
1770  const k4a_float2_t *source_point2d,
1771  const float source_depth_mm,
1772  const k4a_calibration_type_t source_camera,
1773  const k4a_calibration_type_t target_camera,
1774  k4a_float3_t *target_point3d_mm,
1775  int *valid);
1776 
1825 K4A_EXPORT k4a_result_t k4a_calibration_3d_to_2d(const k4a_calibration_t *calibration,
1826  const k4a_float3_t *source_point3d_mm,
1827  const k4a_calibration_type_t source_camera,
1828  const k4a_calibration_type_t target_camera,
1829  k4a_float2_t *target_point2d,
1830  int *valid);
1831 
1887 K4A_EXPORT k4a_result_t k4a_calibration_2d_to_2d(const k4a_calibration_t *calibration,
1888  const k4a_float2_t *source_point2d,
1889  const float source_depth_mm,
1890  const k4a_calibration_type_t source_camera,
1891  const k4a_calibration_type_t target_camera,
1892  k4a_float2_t *target_point2d,
1893  int *valid);
1894 
1922 
1938 K4A_EXPORT void k4a_transformation_destroy(k4a_transformation_t transformation_handle);
1939 
1983  const k4a_image_t depth_image,
1984  k4a_image_t transformed_depth_image);
1985 
2034  const k4a_image_t depth_image,
2035  const k4a_image_t color_image,
2036  k4a_image_t transformed_color_image);
2037 
2086  const k4a_image_t depth_image,
2087  const k4a_calibration_type_t camera,
2088  k4a_image_t xyz_image);
2089 
2094 #ifdef __cplusplus
2095 }
2096 #endif
2097 
2098 #endif /* K4A_H */
k4a_image_t k4a_capture_get_color_image(k4a_capture_t capture_handle)
Get the color image associated with the given capture.
k4a_result_t k4a_transformation_depth_image_to_point_cloud(k4a_transformation_t transformation_handle, const k4a_image_t depth_image, const k4a_calibration_type_t camera, k4a_image_t xyz_image)
Transforms the depth image into 3 planar images representing X, Y and Z-coordinates of corresponding ...
Calibration type representing device calibration.
Definition: k4atypes.h:1014
uint32_t k4a_image_get_white_balance(k4a_image_t image_handle)
Get the image white balance.
k4a_transformation_t k4a_transformation_create(const k4a_calibration_t *calibration)
Get handle to transformation handle.
Structure to define hardware version.
Definition: k4atypes.h:1056
uint32_t k4a_device_get_installed_count(void)
Gets the number of connected devices.
k4a_result_t k4a_device_start_imu(k4a_device_t device_handle)
Starts the IMU sample stream.
k4a_result_t
Result code returned by Azure Kinect APIs.
Definition: k4atypes.h:217
k4a_result_t k4a_set_debug_message_handler(k4a_logging_message_cb_t *message_cb, void *message_cb_context, k4a_log_level_t min_level)
Sets and clears the callback function to recieve debug messages from the Azure Kinect device...
int k4a_image_get_height_pixels(k4a_image_t image_handle)
Get the image height in pixels.
k4a_depth_mode_t
Depth sensor capture modes.
Definition: k4atypes.h:289
k4a_result_t k4a_device_open(uint32_t index, k4a_device_t *device_handle)
Open an Azure Kinect device.
k4a_result_t k4a_device_get_calibration(k4a_device_t device_handle, const k4a_depth_mode_t depth_mode, const k4a_color_resolution_t color_resolution, k4a_calibration_t *calibration)
Get the camera calibration for the entire Azure Kinect device.
Handle to an Azure Kinect capture.
Definition: k4atypes.h:122
k4a_result_t k4a_device_get_color_control_capabilities(k4a_device_t device_handle, k4a_color_control_command_t command, bool *supports_auto, int32_t *min_value, int32_t *max_value, int32_t *step_value, int32_t *default_value, k4a_color_control_mode_t *default_mode)
Get the Azure Kinect color sensor control capabilities.
void k4a_capture_reference(k4a_capture_t capture_handle)
Add a reference to a capture.
k4a_buffer_result_t
Result code returned by Azure Kinect APIs.
Definition: k4atypes.h:231
uint8_t * k4a_image_get_buffer(k4a_image_t image_handle)
Get the image buffer.
k4a_image_t k4a_capture_get_ir_image(k4a_capture_t capture_handle)
Get the IR image associated with the given capture.
void k4a_image_set_iso_speed(k4a_image_t image_handle, uint32_t iso_speed)
Set the ISO speed of the image.
k4a_result_t k4a_capture_create(k4a_capture_t *capture_handle)
Create an empty capture object.
k4a_result_t k4a_device_set_color_control(k4a_device_t device_handle, k4a_color_control_command_t command, k4a_color_control_mode_t mode, int32_t value)
Set the Azure Kinect color sensor control value.
void k4a_image_reference(k4a_image_t image_handle)
Add a reference to the k4a_image_t.
IMU sample.
Definition: k4atypes.h:1114
k4a_result_t k4a_device_get_version(k4a_device_t device_handle, k4a_hardware_version_t *version)
Get the version numbers of the device&#39;s subsystems.
int k4a_image_get_width_pixels(k4a_image_t image_handle)
Get the image width in pixels.
k4a_result_t k4a_device_get_color_control(k4a_device_t device_handle, k4a_color_control_command_t command, k4a_color_control_mode_t *mode, int32_t *value)
Get the Azure Kinect color sensor control value.
void k4a_device_stop_imu(k4a_device_t device_handle)
Stops the IMU capture.
K4A_DEPRECATED_EXPORT void k4a_image_set_timestamp_usec(k4a_image_t image_handle, uint64_t timestamp_usec)
Set the device time stamp, in microseconds, of the image.
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...
k4a_result_t k4a_transformation_depth_image_to_color_camera(k4a_transformation_t transformation_handle, const k4a_image_t depth_image, k4a_image_t transformed_depth_image)
Transforms the depth map into the geometry of the color camera.
k4a_calibration_type_t
Calibration types.
Definition: k4atypes.h:606
int k4a_image_get_stride_bytes(k4a_image_t image_handle)
Get the image stride in bytes.
uint64_t k4a_image_get_system_timestamp_nsec(k4a_image_t image_handle)
Get the image&#39;s system timestamp in nanoseconds.
void k4a_capture_set_temperature_c(k4a_capture_t capture_handle, float temperature_c)
Set the temperature associated with the capture.
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...
k4a_buffer_result_t k4a_device_get_raw_calibration(k4a_device_t device_handle, uint8_t *data, size_t *data_size)
Get the raw calibration blob for the entire Azure Kinect device.
k4a_image_t k4a_capture_get_depth_image(k4a_capture_t capture_handle)
Get the depth image associated with the given capture.
k4a_wait_result_t k4a_device_get_capture(k4a_device_t device_handle, k4a_capture_t *capture_handle, int32_t timeout_in_ms)
Reads a sensor capture.
K4A_DEPRECATED_EXPORT uint64_t k4a_image_get_timestamp_usec(k4a_image_t image_handle)
Get the image&#39;s device timestamp in microseconds.
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:1094
K4A_DEPRECATED_EXPORT void k4a_image_set_exposure_time_usec(k4a_image_t image_handle, uint64_t exposure_usec)
Set the exposure time, in microseconds, of the image.
void k4a_device_stop_cameras(k4a_device_t device_handle)
Stops the color and depth camera capture.
void k4a_image_set_exposure_usec(k4a_image_t image_handle, uint64_t exposure_usec)
Set the exposure time, in microseconds, of the image.
k4a_color_control_mode_t
Color sensor control mode.
Definition: k4atypes.h:572
void k4a_transformation_destroy(k4a_transformation_t transformation_handle)
Destroy transformation handle.
float k4a_capture_get_temperature_c(k4a_capture_t capture_handle)
Get the temperature associated with the capture.
Handle to an Azure Kinect transformation context.
Definition: k4atypes.h:195
k4a_color_resolution_t
Color sensor resolutions.
Definition: k4atypes.h:307
void() k4a_memory_destroy_cb_t(void *buffer, void *context)
Callback function for a memory object being destroyed.
Definition: k4atypes.h:807
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...
void k4a_capture_set_depth_image(k4a_capture_t capture_handle, k4a_image_t image_handle)
Set or add a depth image to the associated capture.
k4a_result_t k4a_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, k4a_image_t *image_handle)
Create an image from a pre-allocated buffer.
k4a_wait_result_t k4a_device_get_imu_sample(k4a_device_t device_handle, k4a_imu_sample_t *imu_sample, int32_t timeout_in_ms)
Reads an IMU sample.
void k4a_image_set_white_balance(k4a_image_t image_handle, uint32_t white_balance)
Set the white balance of the image.
uint64_t k4a_image_get_exposure_usec(k4a_image_t image_handle)
Get the image exposure in microseconds.
uint64_t k4a_image_get_device_timestamp_usec(k4a_image_t image_handle)
Get the image&#39;s device timestamp in microseconds.
Handle to an Azure Kinect device.
Definition: k4atypes.h:66
Two dimensional floating point vector.
Definition: k4atypes.h:1075
void() k4a_logging_message_cb_t(void *context, k4a_log_level_t level, const char *file, const int line, const char *message)
Callback function for debug messages being generated by the Azure Kinect SDK.
Definition: k4atypes.h:781
Handle to an Azure Kinect image.
Definition: k4atypes.h:173
void k4a_device_close(k4a_device_t device_handle)
Closes an Azure Kinect device.
Configuration parameters for an Azure Kinect device.
Definition: k4atypes.h:832
void k4a_image_set_device_timestamp_usec(k4a_image_t image_handle, uint64_t timestamp_usec)
Set the device time stamp, in microseconds, of the image.
k4a_log_level_t
Verbosity levels of debug messaging.
Definition: k4atypes.h:261
k4a_result_t k4a_device_start_cameras(k4a_device_t device_handle, const k4a_device_configuration_t *config)
Starts color and depth camera capture.
void k4a_capture_set_color_image(k4a_capture_t capture_handle, k4a_image_t image_handle)
Set or add a color image to the associated capture.
k4a_color_control_command_t
Color sensor control commands.
Definition: k4atypes.h:461
void k4a_image_release(k4a_image_t image_handle)
Remove a reference from the k4a_image_t.
k4a_buffer_result_t k4a_device_get_serialnum(k4a_device_t device_handle, char *serial_number, size_t *serial_number_size)
Get the Azure Kinect device serial number.
void k4a_capture_release(k4a_capture_t capture_handle)
Release a capture.
size_t k4a_image_get_size(k4a_image_t image_handle)
Get the image buffer size.
k4a_wait_result_t
Result code returned by Azure Kinect APIs.
Definition: k4atypes.h:246
uint32_t k4a_image_get_iso_speed(k4a_image_t image_handle)
Get the image ISO speed.
void k4a_image_set_system_timestamp_nsec(k4a_image_t image_handle, uint64_t timestamp_nsec)
Set the system time stamp, in nanoseconds, of the image.
k4a_image_format_t k4a_image_get_format(k4a_image_t image_handle)
Get the format of the image.
k4a_result_t k4a_device_get_sync_jack(k4a_device_t device_handle, bool *sync_in_jack_connected, bool *sync_out_jack_connected)
Get the device jack status for the synchronization in and synchronization out connectors.
k4a_result_t k4a_image_create(k4a_image_format_t format, int width_pixels, int height_pixels, int stride_bytes, k4a_image_t *image_handle)
Create an image.
k4a_result_t k4a_transformation_color_image_to_depth_camera(k4a_transformation_t transformation_handle, const k4a_image_t depth_image, const k4a_image_t color_image, k4a_image_t transformed_color_image)
Transforms a color image into the geometry of the depth camera.
k4a_image_format_t
Image format type.
Definition: k4atypes.h:329
k4a_result_t k4a_calibration_get_from_raw(char *raw_calibration, size_t raw_calibration_size, const k4a_depth_mode_t depth_mode, const k4a_color_resolution_t color_resolution, k4a_calibration_t *calibration)
Get the camera calibration for a device from a raw calibration blob.
void k4a_capture_set_ir_image(k4a_capture_t capture_handle, k4a_image_t image_handle)
Set or add an IR image to the associated capture.