zed_interface.h
Go to the documentation of this file.
1 #ifndef __INTERFACE_ZED_H
2 #define __INTERFACE_ZED_H
3 
4 #include "types_c.h"
5 #include <stdbool.h>
6 #include <cuda.h>
7 #include <cuda_runtime.h>
8 
13 //#define DEBUG
14 #ifdef _WIN32
15 #ifdef INTERFACE_NOEXPORT
16 #define INTERFACE_API
17 #else
18 #ifdef INTERFACE_EXPORT
19 #define INTERFACE_API __declspec(dllexport)
20 #else
21 #define INTERFACE_API __declspec(dllimport)
22 #endif
23 #endif
24 #else
25 #define INTERFACE_API
26 #endif
27 
28 #ifdef __cplusplus
29 extern "C" {
30 #endif
31 
32 
36  INTERFACE_API void sl_unload_all_instances();
37 
42  INTERFACE_API void sl_unload_instance(int camera_id);
43 
49  INTERFACE_API bool sl_find_usb_device(enum USB_DEVICE device);
50 
57  INTERFACE_API bool sl_create_camera(int camera_id);
58 
64  INTERFACE_API bool sl_is_opened(int camera_id);
65 
78  INTERFACE_API int sl_open_camera(int camera_id, struct SL_InitParameters *init_parameters, const char* path_svo, const char* ip, int stream_port, const char* output_file, const char* opt_settings_path, const char* opencv_calib_path);
79 
84  INTERFACE_API CUcontext sl_get_cuda_context(int camera_id);
85 
90  INTERFACE_API struct SL_InitParameters* sl_get_init_parameters(int camera_id);
91 
97  INTERFACE_API struct SL_RuntimeParameters* sl_get_runtime_parameters(int camera_id);
98 
105 
110  INTERFACE_API void sl_close_camera(int camera_id);
111 
118  INTERFACE_API int sl_set_region_of_interest(int camera_id, void* roi_mask);
125  INTERFACE_API int sl_grab(int camera_id, struct SL_RuntimeParameters *runtime);
126 
134  INTERFACE_API void sl_get_device_list(struct SL_DeviceProperties device_list[MAX_CAMERA_PLUGIN], int* nb_devices);
135 
142  INTERFACE_API void sl_get_streaming_device_list(struct SL_StreamingProperties streaming_device_list[MAX_CAMERA_PLUGIN], int* nb_devices);
143 
149  INTERFACE_API int sl_reboot(int sn, bool full_reboot);
150 
162  INTERFACE_API int sl_enable_recording(int camera_id, const char* filename, enum SL_SVO_COMPRESSION_MODE compression_mode, unsigned int bitrate, int target_fps, bool transcode);
163 
168  INTERFACE_API struct SL_RecordingStatus* sl_get_recording_status(int camera_id);
173  INTERFACE_API void sl_disable_recording(int camera_id);
174 
180  INTERFACE_API struct SL_RecordingParameters* sl_get_recording_parameters(int camera_id);
181 
187  INTERFACE_API void sl_pause_recording(int camera_id, bool status);
188 
197  INTERFACE_API int sl_enable_positional_tracking(int camera_id, struct SL_PositionalTrackingParameters * tracking_param, const char* area_file_path);
198 
221  INTERFACE_API void sl_disable_positional_tracking(int camera_id, const char *area_file_path);
222 
229  INTERFACE_API int sl_save_area_map(int camera_id, const char* area_file_path);
230 
236  INTERFACE_API int sl_get_area_export_state(int camera_id);
237 
245  INTERFACE_API void sl_set_svo_position(int camera_id, int frame_number);
246 
252  INTERFACE_API float sl_get_camera_fps(int camera_id);
253 
259  INTERFACE_API float sl_get_current_fps(int camera_id);
260 
266  int INTERFACE_API sl_get_width(int camera_id);
267 
273  int INTERFACE_API sl_get_height(int camera_id);
274 
280  INTERFACE_API int sl_get_confidence_threshold(int camera_id);
281 
289  INTERFACE_API struct SL_CameraInformation* sl_get_camera_information(int camera_id, int res_width, int res_height);
290 
296  INTERFACE_API void sl_update_self_calibration(int camera_id);
297 
304  INTERFACE_API struct SL_CalibrationParameters* sl_get_calibration_parameters(int camera_id, bool raw_params);
305 
311  INTERFACE_API struct SL_SensorsConfiguration* sl_get_sensors_configuration(int camera_id);
312 
319  INTERFACE_API void sl_get_camera_imu_transform(int camera_id, struct SL_Vector3 *translation, struct SL_Quaternion *rotation);
320 
326  INTERFACE_API int sl_get_input_type(int camera_id);
327 
333  INTERFACE_API int sl_get_zed_serial(int camera_id);
334 
340  INTERFACE_API int sl_get_camera_firmware(int camera_id);
341 
347  INTERFACE_API int sl_get_sensors_firmware(int camera_id);
348 
354  INTERFACE_API int sl_get_camera_model(int camera_id);
355 
361  INTERFACE_API unsigned long long sl_get_image_timestamp(int camera_id);
362 
368  INTERFACE_API unsigned long long sl_get_current_timestamp(int camera_id);
369 
375  INTERFACE_API int sl_get_svo_number_of_frames(int camera_id);
376 
383  INTERFACE_API void sl_set_camera_settings(int camera_id, enum SL_VIDEO_SETTINGS mode, int value);
384 
393  INTERFACE_API int sl_set_roi_for_aec_agc(int camera_id, enum SL_SIDE side, struct SL_Rect* roi, bool reset);
394 
401  INTERFACE_API int sl_get_camera_settings(int camera_id, enum SL_VIDEO_SETTINGS mode);
402 
410  INTERFACE_API int sl_get_roi_for_aec_agc(int id, enum SL_SIDE side, struct SL_Rect* roi);
411 
417  INTERFACE_API float sl_get_depth_min_range_value(int camera_id);
418 
424  INTERFACE_API float sl_get_depth_max_range_value(int camera_id);
425 
433  INTERFACE_API int sl_get_current_min_max_depth(int camera_id,float* min, float* max);
434 
439  INTERFACE_API int sl_get_number_zed_connected();
440 
445  INTERFACE_API char* sl_get_sdk_version();
446 
454  INTERFACE_API int sl_convert_coordinate_system(struct SL_Quaternion* rotation, struct SL_Vector3* translation, enum SL_COORDINATE_SYSTEM coord_system_src, enum SL_COORDINATE_SYSTEM coord_system_dest);
455 
462  //INTERFACE_API void sl_get_sdk_version(int *major, int *minor, int *patch);
463 
469  INTERFACE_API int sl_get_svo_position(int camera_id);
470 
476  INTERFACE_API unsigned int sl_get_frame_dropped_count(int camera_id);
477 
478 
482 
488  INTERFACE_API bool sl_is_positional_tracking_enabled(int camera_id);
489 
500  INTERFACE_API int sl_get_position_at_target_frame(int camera_id, struct SL_Quaternion *rotation, struct SL_Vector3 *position, struct SL_Quaternion *target_quaternion, struct SL_Vector3 *target_translation, enum SL_REFERENCE_FRAME reference_frame);
508  INTERFACE_API int sl_get_position_data(int camera_id, struct SL_PoseData *poseData, enum SL_REFERENCE_FRAME reference_frame);
517  INTERFACE_API int sl_get_position(int camera_id, struct SL_Quaternion *rotation, struct SL_Vector3 *position, enum SL_REFERENCE_FRAME reference_frame);
525  INTERFACE_API int sl_get_position_array(int camera_id, float* pose, enum SL_REFERENCE_FRAME reference_frame);
526 
534  INTERFACE_API int sl_reset_positional_tracking(int camera_id, struct SL_Quaternion rotation, struct SL_Vector3 translation);
544  INTERFACE_API int sl_reset_positional_tracking_with_offset(int camera_id, struct SL_Quaternion rotation, struct SL_Vector3 translation, struct SL_Quaternion target_quaternion, struct SL_Vector3 target_translation);
552  INTERFACE_API int sl_set_imu_prior_orientation(int camera_id, struct SL_Quaternion rotation);
560  INTERFACE_API int sl_get_imu_orientation(int camera_id, struct SL_Quaternion *quat, enum SL_TIME_REFERENCE time_reference);
568  INTERFACE_API int sl_get_sensors_data(int camera_id, struct SL_SensorData *data, enum SL_TIME_REFERENCE time_reference);
569 
570 
574 
588  INTERFACE_API void sl_spatial_mapping_merge_chunks(int camera_id, int nb_faces, int* nb_vertices, int* nb_triangles, int* nb_updated_submeshes, int* updated_indices, int* nb_vertices_tot, int* nb_triangles_tot, const int max_submesh);
589 
600  INTERFACE_API int sl_enable_spatial_mapping(int camera_id, struct SL_SpatialMappingParameters* mapping_param);
605  INTERFACE_API void sl_disable_spatial_mapping(int camera_id);
606 
618  INTERFACE_API void sl_pause_spatial_mapping(int camera_id, bool status);
623  INTERFACE_API void sl_request_mesh_async(int camera_id);
629  INTERFACE_API int sl_get_mesh_request_status_async(int camera_id);
635  INTERFACE_API enum SL_SPATIAL_MAPPING_STATE sl_get_spatial_mapping_state(int camera_id);
648  INTERFACE_API int sl_update_mesh(int camera_id, int* nb_vertices_per_submesh, int* nb_triangles_per_submesh, int* nb_submeshes, int* updated_indices, int* nb_vertices_tot, int* nb_triangles_tot, const int max_submesh);
660  INTERFACE_API int sl_retrieve_mesh(int camera_id, float* vertices, int* triangles, float* uvs, unsigned char* texture_ptr, const int max_submeshes);
673  INTERFACE_API int sl_update_chunks(int camera_id, int* nb_vertices_per_submesh, int* nb_triangles_per_submesh, int* nb_submeshes, int* updated_indices, int* nb_vertices_tot, int* nb_triangles_tot, const int max_submesh);
685  INTERFACE_API int sl_retrieve_chunks(int camera_id, float* vertices, int* triangles, float* uvs, unsigned char* texture_ptr, const int max_submesh);
686 
693  INTERFACE_API int sl_update_fused_point_cloud(int camera_id, int* nb_vertices_tot);
700  INTERFACE_API int sl_retrieve_fused_point_cloud(int camera_id, float* vertices);
706  INTERFACE_API int sl_extract_whole_spatial_map(int camera_id);
714  INTERFACE_API bool sl_save_mesh(int camera_id, const char* filename, enum SL_MESH_FILE_FORMAT format);
722  INTERFACE_API bool sl_save_point_cloud(int c_id, const char* filename, enum SL_MESH_FILE_FORMAT format);
737  INTERFACE_API bool sl_load_mesh(int camera_id, const char* filename, int* nb_vertices_per_submesh, int* nb_triangles_per_submesh, int* num_submeshes, int* updated_indices, int* nb_vertices_tot, int* nb_triangles_tot, int* textures_size,const int max_submesh);
751  INTERFACE_API bool sl_apply_texture(int camera_id, int* nb_vertices_per_submesh, int* nb_triangles_per_submesh, int* nb_updated_submeshes, int* updated_indices, int* nb_vertices_tot, int* nb_triangles_tot, int* textures_size, const int max_submesh);
765  INTERFACE_API bool sl_filter_mesh(int camera_id, enum SL_MESH_FILTER filter_params, int* nb_vertices_per_submesh, int* nb_triangles_per_submesh, int* nb_updated_submeshes, int* updated_indices, int* nb_vertices_tot, int* nb_triangles_tot, const int max_submesh);
773  INTERFACE_API void sl_spatial_mapping_get_gravity_estimation(int camera_id, struct SL_Vector3 *gravity);
774 
775 
777 
785  INTERFACE_API int sl_update_whole_mesh(int camera_id, int* nb_vertices, int* nb_triangles);
796  INTERFACE_API int sl_retrieve_whole_mesh(int camera_id, float* vertices, int* triangles, float* uvs, unsigned char* texture_ptr);
807  INTERFACE_API bool sl_load_whole_mesh(int camera_id, const char* filename, int* nb_vertices, int* nb_triangles, int* texture_size);
816  INTERFACE_API bool sl_apply_whole_texture(int camera_id, int* nb_vertices, int* nb_triangles, int* texture_size);
824  INTERFACE_API bool sl_filter_whole_mesh(int camera_id, enum SL_MESH_FILTER filter_params, int* nb_vertices, int* nb_triangles);
825 
826 
830 
840  INTERFACE_API struct SL_PlaneData* sl_find_floor_plane(int camera_id, struct SL_Quaternion *reset_quaternion, struct SL_Vector3* reset_translation, struct SL_Quaternion prior_rotation, struct SL_Vector3 prior_translation);
848  INTERFACE_API struct SL_PlaneData* sl_find_plane_at_hit(int camera_id, struct SL_Vector2 pixel, bool thres);
858  INTERFACE_API int sl_convert_floorplane_to_mesh(int camera_id, float* vertices, int* triangles, int* nb_vertices_tot, int* nb_triangles_tot);
868  INTERFACE_API int sl_convert_hitplane_to_mesh(int camera_id, float* vertices, int* triangles, int* nb_vertices_tot, int* nb_triangles_tot);
869 
870 
874 
887  INTERFACE_API int sl_retrieve_measure(int camera_id, void* measure_ptr, enum SL_MEASURE type, enum SL_MEM mem, int width, int height);
900  INTERFACE_API int sl_retrieve_image(int camera_id, void* image_ptr, enum SL_VIEW type, enum SL_MEM mem, int width, int height);
901 
909  INTERFACE_API int sl_convert_image(void* image_in_ptr, void* image_signed_ptr, cudaStream_t stream);
910 
914 
937  INTERFACE_API int sl_enable_streaming(int camera_id, enum SL_STREAMING_CODEC codec, unsigned int bitrate, unsigned short port, int gop_size, int adaptative_bitrate, int chunk_size, int target_framerate);
938 
943  INTERFACE_API void sl_disable_streaming(int camera_id);
949  INTERFACE_API int sl_is_streaming_enabled(int camera_id);
950 
955  INTERFACE_API struct SL_StreamingParameters* sl_get_streaming_parameters(int camera_id);
956 
960 
968  INTERFACE_API int sl_save_current_image(int camera_id, enum SL_VIEW view, const char* file_name);
976  INTERFACE_API int sl_save_current_depth(int camera_id, enum SL_SIDE side, const char* file_name);
984  INTERFACE_API int sl_save_current_point_cloud(int camera_id, enum SL_SIDE side, const char* file_name);
985 
986 
987 
988 #if WITH_OBJECT_DETECTION
989 
993 
1000  INTERFACE_API struct SL_AI_Model_status* sl_check_AI_model_status(enum SL_AI_MODELS model, int gpu_id);
1001 
1008  INTERFACE_API int sl_optimize_AI_model(enum SL_AI_MODELS model, int gpu_id);
1009 
1029  INTERFACE_API int sl_enable_objects_detection(int camera_id, struct SL_ObjectDetectionParameters* object_detection_parameters);
1030 
1037 
1048  INTERFACE_API void sl_pause_objects_detection(int camera_id, bool status);
1055  INTERFACE_API void sl_disable_objects_detection(int camera_id);
1056 
1062  INTERFACE_API int sl_generate_unique_id(char* uuid);
1063 
1072  INTERFACE_API int sl_ingest_custom_box_objects(int camera_id, int nb_objects, struct SL_CustomBoxObjectData* objects_in);
1073 
1081  INTERFACE_API int sl_retrieve_objects(int camera_id, struct SL_ObjectDetectionRuntimeParameters* object_detection_runtime_parameters, struct SL_Objects* objects);
1082 
1089  INTERFACE_API int sl_update_objects_batch(int camera_id, int* nb_batches);
1090 
1125  INTERFACE_API int sl_get_objects_batch(int camera_id, int index, struct SL_ObjectsBatch* objs_batch);
1126 
1127 
1128  INTERFACE_API int sl_get_objects_batch_csharp(int camera_id, int index, int* nb_data, int* id, int* label, int* sublabel, int* tracking_state,
1129  struct SL_Vector3 positions[MAX_TRAJECTORY_SIZE], float position_covariances[MAX_TRAJECTORY_SIZE][6], struct SL_Vector3 velocities[MAX_TRAJECTORY_SIZE], unsigned long long timestamps[MAX_TRAJECTORY_SIZE],
1130  struct SL_Vector2 bounding_boxes_2d[MAX_TRAJECTORY_SIZE][4], struct SL_Vector3 bounding_boxes[MAX_TRAJECTORY_SIZE][8], float confidences[MAX_TRAJECTORY_SIZE], int action_states[MAX_TRAJECTORY_SIZE],
1131  struct SL_Vector2 keypoints_2d[MAX_TRAJECTORY_SIZE][18], struct SL_Vector3 keypoints[MAX_TRAJECTORY_SIZE][18], struct SL_Vector2 head_bounding_boxes_2d[MAX_TRAJECTORY_SIZE][4], struct SL_Vector3 head_bounding_boxes[MAX_TRAJECTORY_SIZE][8],
1132  struct SL_Vector3 head_positions[MAX_TRAJECTORY_SIZE], float keypoints_confidences[MAX_TRAJECTORY_SIZE][18]);
1133 #endif
1134 #ifdef __cplusplus
1135 }
1136 #endif
1137 
1138 #ifdef __cplusplus
1139 extern "C" {
1140 #endif
1141 
1145 
1154  INTERFACE_API void* sl_mat_create_new(int width, int height, enum SL_MAT_TYPE type, enum SL_MEM mem);
1159  INTERFACE_API void* sl_mat_create_new_empty();
1165  INTERFACE_API bool sl_mat_is_init(void* ptr);
1172  INTERFACE_API void sl_mat_free(void* ptr, enum SL_MEM mem);
1178  INTERFACE_API void sl_mat_get_infos(void* ptr, char* buffer);
1179 
1180  // GET values
1190  INTERFACE_API int sl_mat_get_value_uchar(void* ptr, int col, int row, unsigned char* value, enum SL_MEM mem);
1200  INTERFACE_API int sl_mat_get_value_uchar2(void* ptr, int col, int row, struct SL_Uchar2* value, enum SL_MEM mem);
1210  INTERFACE_API int sl_mat_get_value_uchar3(void* ptr, int col, int row, struct SL_Uchar3 * value, enum SL_MEM mem);
1220  INTERFACE_API int sl_mat_get_value_uchar4(void* ptr, int col, int row, struct SL_Uchar4* value, enum SL_MEM mem);
1221 
1231  INTERFACE_API int sl_mat_get_value_float(void* ptr, int col, int row, float* value, enum SL_MEM mem);
1241  INTERFACE_API int sl_mat_get_value_float2(void* ptr, int col, int row, struct SL_Vector2 * value, enum SL_MEM mem);
1251  INTERFACE_API int sl_mat_get_value_float3(void* ptr, int col, int row, struct SL_Vector3 * value, enum SL_MEM mem);
1261  INTERFACE_API int sl_mat_get_value_float4(void* ptr, int col, int row, struct SL_Vector4 * value, enum SL_MEM mem);
1262 
1263  // SET VALUE
1273  INTERFACE_API int sl_mat_set_value_uchar(void* ptr, int col, int row, unsigned char value, enum SL_MEM mem);
1283  INTERFACE_API int sl_mat_set_value_uchar2(void* ptr, int col, int row, struct SL_Uchar2 value, enum SL_MEM mem);
1293  INTERFACE_API int sl_mat_set_value_uchar3(void* ptr, int col, int row, struct SL_Uchar3 value, enum SL_MEM mem);
1303  INTERFACE_API int sl_mat_set_value_uchar4(void* ptr, int col, int row, struct SL_Uchar4 value, enum SL_MEM mem);
1313  INTERFACE_API int sl_mat_set_value_float(void* ptr, int col, int row, float value, enum SL_MEM mem);
1323  INTERFACE_API int sl_mat_set_value_float2(void* ptr, int col, int row, struct SL_Vector2 value, enum SL_MEM mem);
1333  INTERFACE_API int sl_mat_set_value_float3(void* ptr, int col, int row, struct SL_Vector3 value, enum SL_MEM mem);
1343  INTERFACE_API int sl_mat_set_value_float4(void* ptr, int col, int row, struct SL_Vector4 value, enum SL_MEM mem);
1344 
1345  //SET TO
1353  INTERFACE_API int sl_mat_set_to_uchar(void* ptr, unsigned char value, enum SL_MEM mem);
1361  INTERFACE_API int sl_mat_set_to_uchar2(void* ptr, struct SL_Uchar2 value, enum SL_MEM mem);
1369  INTERFACE_API int sl_mat_set_to_uchar3(void* ptr, struct SL_Uchar3 value, enum SL_MEM mem);
1377  INTERFACE_API int sl_mat_set_to_uchar4(void* ptr, struct SL_Uchar4 value, enum SL_MEM mem);
1385  INTERFACE_API int sl_mat_set_to_float(void* ptr, float value, enum SL_MEM mem);
1393  INTERFACE_API int sl_mat_set_to_float2(void* ptr, struct SL_Vector2 value, enum SL_MEM mem);
1401  INTERFACE_API int sl_mat_set_to_float3(void* ptr, struct SL_Vector3 value, enum SL_MEM mem);
1409  INTERFACE_API int sl_mat_set_to_float4(void* ptr, struct SL_Vector4 value, enum SL_MEM mem);
1410 
1416  INTERFACE_API int sl_mat_update_cpu_from_gpu(void* ptr);
1422  INTERFACE_API int sl_mat_update_gpu_from_cpu(void* ptr);
1430  INTERFACE_API int sl_mat_copy_to(void* ptr, void* ptr_dest, enum SL_COPY_TYPE cpy_type);
1431 
1438  INTERFACE_API int sl_mat_read(void* ptr, const char* file_path);
1445  INTERFACE_API int sl_mat_write(void* ptr, const char* file_path);
1451  INTERFACE_API int sl_mat_get_width(void* ptr);
1457  INTERFACE_API int sl_mat_get_height(void* ptr);
1463  INTERFACE_API int sl_mat_get_channels(void* ptr);
1469  INTERFACE_API int sl_mat_get_memory_type(void* ptr);
1470 
1476  INTERFACE_API int sl_mat_get_data_type(void* ptr);
1482  INTERFACE_API int sl_mat_get_pixel_bytes(void* ptr);
1488  INTERFACE_API int sl_mat_get_step(void* ptr, enum SL_MEM mem);
1494  INTERFACE_API int sl_mat_get_step_bytes(void* ptr, enum SL_MEM mem);
1500  INTERFACE_API int sl_mat_get_width_bytes(void* ptr);
1505  INTERFACE_API bool sl_mat_is_memory_owner(void* ptr);
1511  INTERFACE_API struct SL_Resolution sl_mat_get_resolution(void* ptr);
1520  INTERFACE_API void sl_mat_alloc(void* ptr, int width, int height, enum SL_MAT_TYPE type, enum SL_MEM mem);
1529  INTERFACE_API int sl_mat_set_from(void* ptr, void* ptr_source, enum SL_COPY_TYPE copy_type);
1536  INTERFACE_API int* sl_mat_get_ptr(void* ptr, enum SL_MEM mem);
1542  INTERFACE_API int sl_mat_clone(void* ptr, void* ptr_source);
1543 
1549  INTERFACE_API void sl_mat_swap(void* ptr_1, void* ptr_2);
1550 
1551 #ifdef __cplusplus
1552 }
1553 #endif
1554 
1555 #endif
contains AI model status.
Definition: types_c.h:1442
Definition: types_c.h:1030
Structure containing information of a single camera (serial number, model, input type,...
Definition: types_c.h:1134
Container to store the externally detected objects. The objects can be ingested using sl_ingest_custo...
Definition: types_c.h:1699
Definition: types_c.h:994
Definition: types_c.h:792
Definition: types_c.h:1451
Definition: types_c.h:1527
Objects batch structure.
Definition: types_c.h:1767
Definition: types_c.h:1736
Definition: types_c.h:115
Definition: types_c.h:97
Definition: types_c.h:1153
Quaternion.
Definition: types_c.h:22
Sets the recording parameters.
Definition: types_c.h:1230
Recording structure that contains information about SVO.
Definition: types_c.h:1210
Definition: types_c.h:1793
Resolution.
Definition: types_c.h:780
Definition: types_c.h:952
Sensor Data structure.
Definition: types_c.h:193
Definition: types_c.h:1087
Definition: types_c.h:1370
Sets the streaming parameters.
Definition: types_c.h:1270
Definition: types_c.h:1342
uchar2
Definition: types_c.h:59
uchar3
Definition: types_c.h:67
uchar4
Definition: types_c.h:76
Vector2.
Definition: types_c.h:32
Vector3.
Definition: types_c.h:40
Vector4.
Definition: types_c.h:49
SL_COORDINATE_SYSTEM
Lists available coordinates systems for positional tracking and 3D measures.
Definition: types_c.h:281
SL_SPATIAL_MAPPING_STATE
Gives the spatial mapping state.
Definition: types_c.h:490
SL_MESH_FILE_FORMAT
Lists available mesh file formats.
Definition: types_c.h:518
SL_AI_MODELS
Lists available AI moles.
Definition: types_c.h:656
SL_STREAMING_CODEC
List of codec.
Definition: types_c.h:380
SL_MAT_TYPE
List available Mat formats.
Definition: types_c.h:584
SL_VIDEO_SETTINGS
Lists available camera settings for the ZED camera (contrast, hue, saturation, gain....
Definition: types_c.h:389
SL_TIME_REFERENCE
Lists specific and particular timestamps.
Definition: types_c.h:372
SL_SIDE
Definition: types_c.h:339
SL_REFERENCE_FRAME
Defines which type of position matrix is used to store camera path and pose.
Definition: types_c.h:355
SL_MESH_FILTER
Lists available mesh filtering intensity.
Definition: types_c.h:509
SL_MEM
List available memory type.
Definition: types_c.h:312
SL_SVO_COMPRESSION_MODE
Lists available compression modes for SVO recording.
Definition: types_c.h:572
SL_VIEW
Lists available views.
Definition: types_c.h:436
SL_COPY_TYPE
List available copy operation on Mat.
Definition: types_c.h:561
SL_MEASURE
Lists retrievable measures.
Definition: types_c.h:411
INTERFACE_API struct SL_CameraInformation * sl_get_camera_information(int camera_id, int res_width, int res_height)
Returns the calibration parameters, serial number and other information about the camera being used.
INTERFACE_API int sl_mat_get_value_uchar3(void *ptr, int col, int row, struct SL_Uchar3 *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API int sl_mat_get_value_uchar(void *ptr, int col, int row, unsigned char *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API void * sl_mat_create_new(int width, int height, enum SL_MAT_TYPE type, enum SL_MEM mem)
Creates a Mat with the given resolution.
INTERFACE_API struct SL_SpatialMappingParameters * sl_get_spatial_mapping_parameters(int camera_id)
Returns the spatial mapping parameters used. Correspond to the structure send when the enableSpatialM...
INTERFACE_API int sl_mat_get_value_float3(void *ptr, int col, int row, struct SL_Vector3 *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API void sl_mat_free(void *ptr, enum SL_MEM mem)
Frees the memory of the Mat.
INTERFACE_API int * sl_mat_get_ptr(void *ptr, enum SL_MEM mem)
Gets a pointer to the Mat.
INTERFACE_API int sl_convert_coordinate_system(struct SL_Quaternion *rotation, struct SL_Vector3 *translation, enum SL_COORDINATE_SYSTEM coord_system_src, enum SL_COORDINATE_SYSTEM coord_system_dest)
Change the coordinate system of a transform matrix.
INTERFACE_API bool sl_create_camera(int camera_id)
Creates a camera with resolution mode, fps and id for linux.
INTERFACE_API int sl_mat_set_value_float(void *ptr, int col, int row, float value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API float sl_get_current_fps(int camera_id)
Returns the current FPS.
INTERFACE_API int sl_mat_set_value_float4(void *ptr, int col, int row, struct SL_Vector4 value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API bool sl_filter_mesh(int camera_id, enum SL_MESH_FILTER filter_params, int *nb_vertices_per_submesh, int *nb_triangles_per_submesh, int *nb_updated_submeshes, int *updated_indices, int *nb_vertices_tot, int *nb_triangles_tot, const int max_submesh)
Filters a mesh to removes triangles while still preserving its overall shaper (though less accurate).
INTERFACE_API int sl_get_camera_firmware(int camera_id)
Gets the ZED camera Current Firmware version.
INTERFACE_API int sl_mat_copy_to(void *ptr, void *ptr_dest, enum SL_COPY_TYPE cpy_type)
Copies data from this Mat to another Mat (deep copy).
INTERFACE_API int sl_retrieve_mesh(int camera_id, float *vertices, int *triangles, float *uvs, unsigned char *texture_ptr, const int max_submeshes)
Retrieves all chunks of the current mesh. Call update_mesh before calling this. Vertex and triangles ...
INTERFACE_API int sl_mat_read(void *ptr, const char *file_path)
Reads an image from a file. Supports .png and .jpeg. Only works if Mat has access to MEM_CPU.
INTERFACE_API int sl_mat_set_to_uchar(void *ptr, unsigned char value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API int sl_mat_set_value_float3(void *ptr, int col, int row, struct SL_Vector3 value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API unsigned int sl_get_frame_dropped_count(int camera_id)
Gets the number of frames dropped since Grab() was called for the first time. Based on camera timesta...
INTERFACE_API int sl_mat_get_value_float4(void *ptr, int col, int row, struct SL_Vector4 *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API void sl_pause_objects_detection(int camera_id, bool status)
Pauses or resumes the object detection processes.
INTERFACE_API struct SL_RecordingParameters * sl_get_recording_parameters(int camera_id)
Returns the recording parameters used. Correspond to the structure send when the sl_enable_recording(...
INTERFACE_API int sl_get_position_at_target_frame(int camera_id, struct SL_Quaternion *rotation, struct SL_Vector3 *position, struct SL_Quaternion *target_quaternion, struct SL_Vector3 *target_translation, enum SL_REFERENCE_FRAME reference_frame)
Gets the current position of the camera and state of the tracking, with an optional offset to the tra...
INTERFACE_API int sl_get_confidence_threshold(int camera_id)
Gets the current confidence threshold value for the disparity map (and by extension the depth map).
INTERFACE_API int sl_get_objects_batch(int camera_id, int index, struct SL_ObjectsBatch *objs_batch)
Gets a batch of detected objects. Need to be called after update_objects_batch().
INTERFACE_API void sl_mat_get_infos(void *ptr, char *buffer)
Returns information about the Mat.
INTERFACE_API struct SL_AI_Model_status * sl_check_AI_model_status(enum SL_AI_MODELS model, int gpu_id)
Check if a corresponding optimized engine is found for the requested Model based on your rig configur...
INTERFACE_API void sl_set_camera_settings(int camera_id, enum SL_VIDEO_SETTINGS mode, int value)
Sets a value in the ZED's camera settings.
INTERFACE_API void sl_spatial_mapping_get_gravity_estimation(int camera_id, struct SL_Vector3 *gravity)
Gets a vector pointing toward the direction of gravity. This is estimated from a 3D scan of the envir...
INTERFACE_API int sl_save_area_map(int camera_id, const char *area_file_path)
Saves the current area learning file. The file will contain spatial memory data generated by the trac...
INTERFACE_API int sl_update_fused_point_cloud(int camera_id, int *nb_vertices_tot)
Updates the fused point cloud (if spatial map type was FUSED_POINT_CLOUD).
INTERFACE_API int sl_get_camera_model(int camera_id)
Gets the ZED Camera model (see SL_MODEL).
INTERFACE_API void sl_disable_streaming(int camera_id)
Disables the streaming initiated by enable_streaming().
INTERFACE_API void sl_pause_recording(int camera_id, bool status)
Pauses or resumes the recording.
INTERFACE_API void sl_get_device_list(struct SL_DeviceProperties device_list[MAX_CAMERA_PLUGIN], int *nb_devices)
Lists all the connected devices with their associated information.
INTERFACE_API int sl_mat_get_value_uchar4(void *ptr, int col, int row, struct SL_Uchar4 *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API char * sl_get_sdk_version()
Returns the version of the currently installed ZED SDK.
INTERFACE_API void sl_disable_positional_tracking(int camera_id, const char *area_file_path)
Initializes and starts the positional tracking processes. This function allows you to enable the posi...
INTERFACE_API int sl_update_chunks(int camera_id, int *nb_vertices_per_submesh, int *nb_triangles_per_submesh, int *nb_submeshes, int *updated_indices, int *nb_vertices_tot, int *nb_triangles_tot, const int max_submesh)
Updates the internal version of the mesh and returns the sizes of the meshes.
INTERFACE_API bool sl_load_whole_mesh(int camera_id, const char *filename, int *nb_vertices, int *nb_triangles, int *texture_size)
Loads a saved mesh file.
INTERFACE_API bool sl_load_mesh(int camera_id, const char *filename, int *nb_vertices_per_submesh, int *nb_triangles_per_submesh, int *num_submeshes, int *updated_indices, int *nb_vertices_tot, int *nb_triangles_tot, int *textures_size, const int max_submesh)
Loads a saved mesh file.
INTERFACE_API bool sl_mat_is_memory_owner(void *ptr)
Returns whether the Mat is the owner of the memory it's accessing.
INTERFACE_API int sl_get_imu_orientation(int camera_id, struct SL_Quaternion *quat, enum SL_TIME_REFERENCE time_reference)
Gets the rotation given by the ZED-M/ZED2 IMU. Returns an error if using ZED (v1) which does not cont...
INTERFACE_API int sl_get_svo_position(int camera_id)
Returns the version of the currently installed ZED SDK.
INTERFACE_API int sl_enable_objects_detection(int camera_id, struct SL_ObjectDetectionParameters *object_detection_parameters)
Initializes and starts the Deep Learning detection module. The object detection module currently su...
INTERFACE_API int sl_save_current_point_cloud(int camera_id, enum SL_SIDE side, const char *file_name)
Writes the point cloud into a file defined by its extension.
INTERFACE_API int sl_mat_get_width_bytes(void *ptr)
Gets the size of each row in bytes.
INTERFACE_API int sl_mat_set_to_uchar4(void *ptr, struct SL_Uchar4 value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API struct SL_CalibrationParameters * sl_get_calibration_parameters(int camera_id, bool raw_params)
Gets the Calibration Parameters.
INTERFACE_API int sl_get_roi_for_aec_agc(int id, enum SL_SIDE side, struct SL_Rect *roi)
Gets the region of interest for automatic exposure/gain computation.
INTERFACE_API void sl_mat_alloc(void *ptr, int width, int height, enum SL_MAT_TYPE type, enum SL_MEM mem)
Allocates memory for the Mat.
INTERFACE_API void sl_unload_all_instances()
Forces unload of all instances.
INTERFACE_API void sl_spatial_mapping_merge_chunks(int camera_id, int nb_faces, int *nb_vertices, int *nb_triangles, int *nb_updated_submeshes, int *updated_indices, int *nb_vertices_tot, int *nb_triangles_tot, const int max_submesh)
Consolidates the chucks from a scan. This is used to turn a lots of small meshes (which are efficient...
INTERFACE_API struct SL_PlaneData * sl_find_plane_at_hit(int camera_id, struct SL_Vector2 pixel, bool thres)
Check for a plane in hte real world at given screen-space coordinates.
INTERFACE_API int sl_mat_get_value_float(void *ptr, int col, int row, float *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API void sl_request_mesh_async(int camera_id)
Starts the mesh generation process in a thread that doesn't block the spatial mapping process.
INTERFACE_API int sl_is_streaming_enabled(int camera_id)
Tells if the streaming is running (true) or still initializing (false).
INTERFACE_API int sl_get_position(int camera_id, struct SL_Quaternion *rotation, struct SL_Vector3 *position, enum SL_REFERENCE_FRAME reference_frame)
Retrieves the estimated position and orientation of the camera in the specified reference frame.
INTERFACE_API int sl_get_svo_number_of_frames(int camera_id)
Gets the total number of frames in the loaded SVO file.
INTERFACE_API bool sl_save_mesh(int camera_id, const char *filename, enum SL_MESH_FILE_FORMAT format)
Saves the scanned mesh in a specific file format.
INTERFACE_API void sl_disable_spatial_mapping(int camera_id)
Disables the Spatial Mapping process.
INTERFACE_API int sl_retrieve_whole_mesh(int camera_id, float *vertices, int *triangles, float *uvs, unsigned char *texture_ptr)
Retrieves the full mesh. Call update_mesh before calling this. Vertex and triangles arrays must be at...
INTERFACE_API int sl_enable_recording(int camera_id, const char *filename, enum SL_SVO_COMPRESSION_MODE compression_mode, unsigned int bitrate, int target_fps, bool transcode)
Creates a file for recording the ZED's output into a .SVO or .AVI video. An SVO is Stereolabs' own fo...
INTERFACE_API void sl_disable_recording(int camera_id)
Disables the recording initiated by enableRecording() and closes the generated file.
INTERFACE_API int sl_save_current_image(int camera_id, enum SL_VIEW view, const char *file_name)
Writes the image into a file defined by its extension.
INTERFACE_API int sl_mat_get_channels(void *ptr)
Gets the number of channels stored in each pixel.
INTERFACE_API struct SL_PositionalTrackingParameters * sl_get_positional_tracking_parameters(int camera_id)
Returns the PositionalTrackingParameters.
INTERFACE_API int sl_save_current_depth(int camera_id, enum SL_SIDE side, const char *file_name)
Writes the depth map into a file defined by its extension.
INTERFACE_API int sl_get_current_min_max_depth(int camera_id, float *min, float *max)
Gets the current range of perceived depth.
INTERFACE_API struct SL_RuntimeParameters * sl_get_runtime_parameters(int camera_id)
Returns the Runtimeparameters used to open the ZED camera.
INTERFACE_API int sl_mat_get_memory_type(void *ptr)
Gets the type of memory (CPU and/or GPU).
INTERFACE_API int sl_enable_positional_tracking(int camera_id, struct SL_PositionalTrackingParameters *tracking_param, const char *area_file_path)
Initializes and starts the positional tracking processes. This function allows you to enable the posi...
INTERFACE_API bool sl_is_opened(int camera_id)
Reports if the camera has been successfully opened.
INTERFACE_API int sl_retrieve_fused_point_cloud(int camera_id, float *vertices)
Retrieves all points of the fused point cloud. Call update_fused_point_cloud before calling this.
INTERFACE_API struct SL_InitParameters * sl_get_init_parameters(int camera_id)
Returns the initparameters used to open the ZED camera.
INTERFACE_API int sl_generate_unique_id(char *uuid)
Generate a UUID like unique ID to help identify and track AI detections.
INTERFACE_API int sl_mat_write(void *ptr, const char *file_path)
Writes the Mat into a file as an image. Only works if Mat has access to MEM_CPU.
INTERFACE_API int sl_mat_clone(void *ptr, void *ptr_source)
Duplicates a Mat by copying all its data into a new one (deep copy).
INTERFACE_API int sl_update_whole_mesh(int camera_id, int *nb_vertices, int *nb_triangles)
Updates the internal version of the whole mesh and returns the size of its data.
INTERFACE_API struct SL_ObjectDetectionParameters * sl_get_object_detection_parameters(int cmaera_id)
Returns the object detection parameters used. Correspond to the structure send when the enableObjectD...
INTERFACE_API int sl_retrieve_image(int camera_id, void *image_ptr, enum SL_VIEW type, enum SL_MEM mem, int width, int height)
Retrieves an image texture from the ZED SDK in a human-viewable format. Image textures work for when ...
INTERFACE_API int sl_mat_set_to_float(void *ptr, float value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API int sl_mat_set_to_uchar2(void *ptr, struct SL_Uchar2 value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API float sl_get_camera_fps(int camera_id)
Returns the camera FPS.
INTERFACE_API int sl_ingest_custom_box_objects(int camera_id, int nb_objects, struct SL_CustomBoxObjectData *objects_in)
Feed the 3D Object tracking function with your own 2D bounding boxes from your own detection algorith...
INTERFACE_API int sl_get_position_array(int camera_id, float *pose, enum SL_REFERENCE_FRAME reference_frame)
Gets the position of the camera and the current state of the ZED Tracking as a float array (4x4).
INTERFACE_API int sl_mat_get_step(void *ptr, enum SL_MEM mem)
Gets the memory 'step' in number/length of elements - how many values make up each row of pixels.
INTERFACE_API int sl_mat_update_cpu_from_gpu(void *ptr)
Copies data from the GPU to the CPU, if possible.
INTERFACE_API int sl_get_camera_settings(int camera_id, enum SL_VIDEO_SETTINGS mode)
Gets the value of a given setting from the ZED camera.
INTERFACE_API void sl_close_camera(int camera_id)
Destroys the camera and disable the textures.
INTERFACE_API struct SL_StreamingParameters * sl_get_streaming_parameters(int camera_id)
Returns the streaming parameters used. Correspond to the structure send when the sl_enable_streaming(...
INTERFACE_API int sl_reset_positional_tracking_with_offset(int camera_id, struct SL_Quaternion rotation, struct SL_Vector3 translation, struct SL_Quaternion target_quaternion, struct SL_Vector3 target_translation)
Resets the tracking with an offset.
INTERFACE_API void sl_mat_swap(void *ptr_1, void *ptr_2)
Swaps the content of the provided Mat (only swaps the pointers, no data copy).
INTERFACE_API int sl_mat_get_width(void *ptr)
Gets the Width of the matrix.
INTERFACE_API int sl_mat_get_data_type(void *ptr)
Gets the type of data (Mat_Type).
INTERFACE_API int sl_mat_set_value_uchar2(void *ptr, int col, int row, struct SL_Uchar2 value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API bool sl_apply_texture(int camera_id, int *nb_vertices_per_submesh, int *nb_triangles_per_submesh, int *nb_updated_submeshes, int *updated_indices, int *nb_vertices_tot, int *nb_triangles_tot, int *textures_size, const int max_submesh)
Applies the scanned texture onto the internal scanned mesh.
INTERFACE_API int sl_mat_set_from(void *ptr, void *ptr_source, enum SL_COPY_TYPE copy_type)
Copies data from another Mat into this one(deep copy).
INTERFACE_API bool sl_mat_is_init(void *ptr)
Tells if the Mat has been initialized.
INTERFACE_API int sl_reboot(int sn, bool full_reboot)
Performs an hardware reset of the ZED 2 / ZED 2i.
INTERFACE_API void sl_disable_objects_detection(int camera_id)
Disables the Object Detection process.
INTERFACE_API struct SL_PlaneData * sl_find_floor_plane(int camera_id, struct SL_Quaternion *reset_quaternion, struct SL_Vector3 *reset_translation, struct SL_Quaternion prior_rotation, struct SL_Vector3 prior_translation)
Looks for a plane in the visible area that is likely to represent the floor.
INTERFACE_API int sl_mat_set_to_float3(void *ptr, struct SL_Vector3 value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API int sl_get_sensors_data(int camera_id, struct SL_SensorData *data, enum SL_TIME_REFERENCE time_reference)
Gets the full Sensor data from the ZED-M/ZED2/ZED2i. Returns an error is using ZED (v1) which does no...
INTERFACE_API int sl_update_objects_batch(int camera_id, int *nb_batches)
Updates the internal batch of detected objects.
INTERFACE_API float sl_get_depth_min_range_value(int camera_id)
Gets the depth min value from InitParameters (see SL_InitParameters::depth_minimum_distance).
INTERFACE_API int sl_get_area_export_state(int camera_id)
Returns the state of the spatial memory export process.
INTERFACE_API int sl_reset_positional_tracking(int camera_id, struct SL_Quaternion rotation, struct SL_Vector3 translation)
Resets the tracking, and re-initializes the position with the given pose.
INTERFACE_API bool sl_is_positional_tracking_enabled(int camera_id)
Gets the current position of the camera and state of the tracking, with an optional offset to the tra...
INTERFACE_API struct SL_RecordingStatus * sl_get_recording_status(int camera_id)
Get the recording information.
int INTERFACE_API sl_get_height(int camera_id)
Returns the height of the current image.
INTERFACE_API int sl_get_sensors_firmware(int camera_id)
Gets the ZED mcu Current Firmware version.
INTERFACE_API void sl_get_streaming_device_list(struct SL_StreamingProperties streaming_device_list[MAX_CAMERA_PLUGIN], int *nb_devices)
List all the streaming devices with their associated information.
INTERFACE_API int sl_mat_set_value_uchar4(void *ptr, int col, int row, struct SL_Uchar4 value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API int sl_mat_set_to_float2(void *ptr, struct SL_Vector2 value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API bool sl_filter_whole_mesh(int camera_id, enum SL_MESH_FILTER filter_params, int *nb_vertices, int *nb_triangles)
Filters a mesh to removes triangles while still preserving its overall shaper (though less accurate).
INTERFACE_API bool sl_apply_whole_texture(int camera_id, int *nb_vertices, int *nb_triangles, int *texture_size)
Applies the scanned texture onto the internal scanned mesh.
INTERFACE_API int sl_mat_set_value_uchar3(void *ptr, int col, int row, struct SL_Uchar3 value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API int sl_get_position_data(int camera_id, struct SL_PoseData *poseData, enum SL_REFERENCE_FRAME reference_frame)
Gets the current position of the camera and state of the tracking, filling a PoseData struck useful f...
INTERFACE_API void sl_unload_instance(int camera_id)
Forces unload of one instance.
INTERFACE_API struct SL_Resolution sl_mat_get_resolution(void *ptr)
Returns the resolution of the image that this Mat holds.
INTERFACE_API int sl_mat_update_gpu_from_cpu(void *ptr)
Copies data from the CPU to the GPU, if possible.
INTERFACE_API struct SL_SensorsConfiguration * sl_get_sensors_configuration(int camera_id)
Gets the Sensors configuration.
INTERFACE_API int sl_mat_set_to_uchar3(void *ptr, struct SL_Uchar3 value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API int sl_set_roi_for_aec_agc(int camera_id, enum SL_SIDE side, struct SL_Rect *roi, bool reset)
Sets the region of interest for automatic exposure/gain computation.
INTERFACE_API int sl_extract_whole_spatial_map(int camera_id)
Extracts the current spatial map from the spatial mapping process.
INTERFACE_API int sl_retrieve_objects(int camera_id, struct SL_ObjectDetectionRuntimeParameters *object_detection_runtime_parameters, struct SL_Objects *objects)
Retrieve objects detected by the object detection module.
INTERFACE_API int sl_open_camera(int camera_id, struct SL_InitParameters *init_parameters, const char *path_svo, const char *ip, int stream_port, const char *output_file, const char *opt_settings_path, const char *opencv_calib_path)
Opens the camera depending on the init parameters.
INTERFACE_API bool sl_save_point_cloud(int c_id, const char *filename, enum SL_MESH_FILE_FORMAT format)
Saves the scanned point cloud in a specific file format.
INTERFACE_API int sl_update_mesh(int camera_id, int *nb_vertices_per_submesh, int *nb_triangles_per_submesh, int *nb_submeshes, int *updated_indices, int *nb_vertices_tot, int *nb_triangles_tot, const int max_submesh)
Updates the internal version of the mesh and returns the sizes of the meshes.
INTERFACE_API int sl_mat_get_pixel_bytes(void *ptr)
Gets the size in bytes of one pixel.
INTERFACE_API int sl_mat_set_value_uchar(void *ptr, int col, int row, unsigned char value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API int sl_mat_get_value_uchar2(void *ptr, int col, int row, struct SL_Uchar2 *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API float sl_get_depth_max_range_value(int camera_id)
Gets the depth max value from InitParameters (see SL_InitParameters::depth_maximum_distance).
INTERFACE_API int sl_get_mesh_request_status_async(int camera_id)
Returns the mesh generation status. Useful for knowing when to update and retrieve the mesh.
INTERFACE_API CUcontext sl_get_cuda_context(int camera_id)
Gets the Camera-created CUDA context for sharing it with other CUDA-capable libraries.
INTERFACE_API bool sl_find_usb_device(enum USB_DEVICE device)
Checks usb devices connected. param device : type of device to find.
INTERFACE_API unsigned long long sl_get_image_timestamp(int camera_id)
Get the Timestamp at the time the frame has been extracted from USB stream. (should be called after a...
INTERFACE_API int sl_convert_hitplane_to_mesh(int camera_id, float *vertices, int *triangles, int *nb_vertices_tot, int *nb_triangles_tot)
Using data from a detected hit plane, updates supplied vertex and triangles arrays with data needed t...
INTERFACE_API int sl_mat_set_to_float4(void *ptr, struct SL_Vector4 value, enum SL_MEM mem)
Fills the entire Mat with the given value.
INTERFACE_API int sl_get_zed_serial(int camera_id)
Gets the ZED Serial Number.
INTERFACE_API void sl_pause_spatial_mapping(int camera_id, bool status)
INTERFACE_API int sl_convert_image(void *image_in_ptr, void *image_signed_ptr, cudaStream_t stream)
Convert Image format from Unsigned char to Signed char, designed for Unreal Engine pipeline,...
INTERFACE_API int sl_get_input_type(int camera_id)
Gets the input type (see SL_INPUT_TYPE).
INTERFACE_API int sl_mat_get_step_bytes(void *ptr, enum SL_MEM mem)
Gets the memory 'step' in bytes - how many bytes make up each row of pixels.
INTERFACE_API int sl_enable_streaming(int camera_id, enum SL_STREAMING_CODEC codec, unsigned int bitrate, unsigned short port, int gop_size, int adaptative_bitrate, int chunk_size, int target_framerate)
Creates a streaming pipeline.
INTERFACE_API unsigned long long sl_get_current_timestamp(int camera_id)
Get the current Timestamp at the time the function is called. Can be compared to the camera Timestamp...
INTERFACE_API int sl_optimize_AI_model(enum SL_AI_MODELS model, int gpu_id)
Optimize the requested model, possible download if the model is not present on the host.
INTERFACE_API int sl_retrieve_chunks(int camera_id, float *vertices, int *triangles, float *uvs, unsigned char *texture_ptr, const int max_submesh)
Retrieves all chunks of the full mesh. Call update_mesh before calling this. Vertex and triangles arr...
INTERFACE_API int sl_mat_get_height(void *ptr)
Gets the Height of the matrix.
INTERFACE_API int sl_retrieve_measure(int camera_id, void *measure_ptr, enum SL_MEASURE type, enum SL_MEM mem, int width, int height)
Retrieves a measure texture from the ZED SDK. Use this to get an individual texture from the last gra...
INTERFACE_API int sl_convert_floorplane_to_mesh(int camera_id, float *vertices, int *triangles, int *nb_vertices_tot, int *nb_triangles_tot)
Using data from a detected floor plane, updates supplied vertex and triangles arrays with data needed...
INTERFACE_API int sl_grab(int camera_id, struct SL_RuntimeParameters *runtime)
Grabs the lastest images from the camera.
INTERFACE_API int sl_mat_get_value_float2(void *ptr, int col, int row, struct SL_Vector2 *value, enum SL_MEM mem)
Returns the value of a specific point in the matrix.
INTERFACE_API int sl_enable_spatial_mapping(int camera_id, struct SL_SpatialMappingParameters *mapping_param)
Initializes and begins the spatial mapping processes.
INTERFACE_API void sl_get_camera_imu_transform(int camera_id, struct SL_Vector3 *translation, struct SL_Quaternion *rotation)
Gets the IMU to Left camera transform matrix.
INTERFACE_API int sl_set_imu_prior_orientation(int camera_id, struct SL_Quaternion rotation)
Sets a prior to the IMU orientation (using a ZED-mini, ZED2 or ZED2i). Prior must come from a externa...
INTERFACE_API int sl_mat_set_value_float2(void *ptr, int col, int row, struct SL_Vector2 value, enum SL_MEM mem)
Sets a value to a specific point in the matrix.
INTERFACE_API void sl_update_self_calibration(int camera_id)
Performs a new self calibration process. In some cases, due to temperature changes or strong vibratio...
INTERFACE_API int sl_get_number_zed_connected()
Gets the number of zed connected.
int INTERFACE_API sl_get_width(int camera_id)
Returns the width of the current image.
INTERFACE_API void sl_set_svo_position(int camera_id, int frame_number)
Sets the playback cursor to the desired frame number in the SVO file. This function allows you to mov...
INTERFACE_API int sl_set_region_of_interest(int camera_id, void *roi_mask)
Defines a region of interest to focus on for all the SDK, discarding other parts.
INTERFACE_API enum SL_SPATIAL_MAPPING_STATE sl_get_spatial_mapping_state(int camera_id)
Gets the current state of spatial mapping.
INTERFACE_API void * sl_mat_create_new_empty()
Creates an empty Mat with the given resolution.