Classes | |
class | PositionalTrackingStatus |
struct | RecordingStatus |
Structure containing information about the status of the recording. More... | |
class | InitParameters |
Class containing the options used to initialize the sl::Camera object. More... | |
struct | RuntimeParameters |
Structure containing parameters that defines the behavior of sl::Camera::grab(). More... | |
class | PositionalTrackingParameters |
Structure containing a set of parameters for the positional tracking module initialization. More... | |
class | SpatialMappingParameters |
Structure containing a set of parameters for the spatial mapping module. More... | |
struct | StreamingParameters |
Structure containing the options used to stream with the ZED SDK. More... | |
struct | RecordingParameters |
Structure containing the options used to record. More... | |
class | BatchParameters |
Structure containing a set of parameters for batch object detection. More... | |
class | ObjectDetectionParameters |
Structure containing a set of parameters for the object detection module. More... | |
class | ObjectDetectionRuntimeParameters |
Structure containing a set of runtime parameters for the object detection module. More... | |
struct | BodyTrackingParameters |
Structure containing a set of parameters for the body tracking module. More... | |
struct | BodyTrackingRuntimeParameters |
Structure containing a set of runtime parameters for the body tracking module. More... | |
class | PlaneDetectionParameters |
Structure containing a set of parameters for the plane detection functionality. More... | |
struct | RegionOfInterestParameters |
class | Camera |
This class serves as the primary interface between the camera and the various features provided by the SDK. More... | |
class | String |
Class defining a string. More... | |
struct | Resolution |
Structure containing the width and height of an image. More... | |
class | Rect |
Class defining a 2D rectangle with top-left corner coordinates and width/height in pixels. More... | |
struct | DeviceProperties |
Structure containing information about the properties of a camera. More... | |
struct | StreamingProperties |
Structure containing information about the properties of a streaming device. More... | |
class | InputType |
Class defining the input type used in the ZED SDK. More... | |
class | AI_Model_status |
Structure containing AI model status. More... | |
class | Matrix3f |
Class representing a generic 3*3 matrix. More... | |
class | Matrix4f |
Class representing a generic 4*4 matrix. More... | |
class | Vector2 |
Class representing a 2-dimensional vector for both CPU and GPU. More... | |
class | Vector3 |
Class representing a 3-dimensional vector for both CPU and GPU. More... | |
class | Vector4 |
Class representing a 4-dimensional vector for both CPU and GPU. More... | |
struct | Timestamp |
Structure representing timestamps with utilities. More... | |
class | Mat |
Class representing 1 to 4-channel matrix of float or uchar, stored on CPU and/or GPU side. More... | |
class | Rotation |
Class representing a rotation for the positional tracking module. More... | |
class | Translation |
Class representing a translation for the positional tracking module. More... | |
class | Orientation |
Class representing an orientation/quaternion for the positional tracking module. More... | |
class | Transform |
Class representing a transformation (translation and rotation) for the positional tracking module. More... | |
struct | CameraParameters |
Structure containing the intrinsic parameters of a camera. More... | |
struct | CalibrationParameters |
Structure containing intrinsic and extrinsic parameters of the camera (translation and rotation). More... | |
struct | SensorParameters |
Structure containing information about a single sensor available in the current device. More... | |
struct | SensorsConfiguration |
Structure containing information about all the sensors available in the current device. More... | |
struct | CameraConfiguration |
Structure containing information about the camera sensor. More... | |
struct | CameraInformation |
Structure containing information of a single camera (serial number, model, input type, etc.). More... | |
class | Pose |
Class containing positional tracking data giving the position and orientation of the camera in 3D space. More... | |
struct | SensorsData |
Structure containing all sensors data (except image sensors) to be used for positional tracking or environment study. More... | |
class | ObjectData |
Class containing data of a detected object such as its bounding_box, label, id and its 3D position. More... | |
class | CustomBoxObjectData |
Class that store externally detected objects. More... | |
class | Objects |
Class containing the results of the object detection module. More... | |
class | BodyData |
Class containing data of a detected body/person such as its bounding_box, id and its 3D position. More... | |
class | Bodies |
Class containing the results of the body tracking module. More... | |
class | ObjectsBatch |
Class containing batched data of a detected objects from the object detection module. More... | |
class | BodiesBatch |
Class containing batched data of a detected bodies/persons from the body tracking module. More... | |
class | CommunicationParameters |
Holds the communication parameter to configure the connection between senders and receiver. More... | |
struct | SVOData |
class | MeshFilterParameters |
Class containing a set of parameters for the mesh filtration functionality. More... | |
class | Chunk |
Class representing a sub-mesh containing local vertices and triangles. More... | |
class | Mesh |
Class representing a mesh and containing the geometric (and optionally texture) data of the scene captured by the spatial mapping module. More... | |
class | Plane |
Class representing a plane defined by a point and a normal, or a plane equation. More... | |
class | PointCloudChunk |
Class representing a sub-point cloud containing local vertices and colors. More... | |
class | FusedPointCloud |
Class representing a fused point cloud and containing the geometric and color data of the scene captured by the spatial mapping module. More... | |
class | FusionConfiguration |
Useful struct to store the Fusion configuration, can be read from /write to a JSON file. More... | |
class | InitFusionParameters |
Holds the options used to initialize the Fusion object. More... | |
class | CameraIdentifier |
Used to identify a specific camera in the Fusion API. More... | |
class | BodyTrackingFusionParameters |
Holds the options used to initialize the body tracking module of the Fusion. More... | |
class | BodyTrackingFusionRuntimeParameters |
Holds the options used to change the behavior of the body tracking module at runtime. More... | |
class | ObjectDetectionFusionParameters |
Holds the options used to initialize the object detection module of the Fusion. More... | |
class | GNSSCalibrationParameters |
Holds the options used for calibrating GNSS / VIO. More... | |
class | PositionalTrackingFusionParameters |
Holds the options used for initializing the positional tracking fusion module. More... | |
class | SpatialMappingFusionParameters |
Sets the spatial mapping parameters. More... | |
class | CameraMetrics |
Holds the metrics of a sender in the fusion process. More... | |
class | FusionMetrics |
Holds the metrics of the fusion process. More... | |
class | ECEF |
Represents a world position in ECEF format. More... | |
class | LatLng |
Represents a world position in LatLng format. More... | |
class | UTM |
Represents a world position in UTM format. More... | |
class | GeoConverter |
Purely static class for Geo functions. More... | |
class | GeoPose |
Holds geographic reference position information. More... | |
class | GNSSData |
Class containing GNSS data to be used for positional tracking as prior. More... | |
class | FusedPositionalTrackingStatus |
Class containing the overall position fusion status. More... | |
class | Fusion |
Holds Fusion process data and functions. More... | |
Enumerations | |
enum class | SIDE |
Lists possible sides on which to get data from. More... | |
enum | FLIP_MODE : int |
Lists possible flip modes of the camera. More... | |
enum class | RESOLUTION |
Lists available resolutions. More... | |
enum class | VIDEO_SETTINGS |
Lists available camera settings for the camera (contrast, hue, saturation, gain, ...). More... | |
enum class | DEPTH_MODE |
Lists available depth computation modes. More... | |
enum class | MEASURE |
Lists retrievable measures. More... | |
enum class | VIEW |
Lists available views. More... | |
enum class | TIME_REFERENCE |
Lists possible time references for timestamps or data. More... | |
enum class | POSITIONAL_TRACKING_STATE |
Lists the different states of positional tracking. More... | |
enum class | ODOMETRY_STATUS |
enum class | SPATIAL_MEMORY_STATUS |
Report the status of current map tracking. More... | |
enum class | POSITIONAL_TRACKING_FUSION_STATUS |
Report the status of the positional tracking fusion. More... | |
enum class | POSITIONAL_TRACKING_MODE |
Lists the mode of positional tracking that can be used. More... | |
enum class | AREA_EXPORTING_STATE |
Lists the different states of spatial memory area export. More... | |
enum class | SPATIAL_MAPPING_STATE |
Lists the different states of spatial mapping. More... | |
enum class | REGION_OF_INTEREST_AUTO_DETECTION_STATE |
Lists the different states of region of interest auto detection. More... | |
enum class | SVO_COMPRESSION_MODE |
Lists available compression modes for SVO recording. More... | |
enum class | UNIT |
Lists available units for measures. More... | |
enum class | COORDINATE_SYSTEM |
Lists available coordinates systems for positional tracking and 3D measures. More... | |
enum class | ERROR_CODE |
Lists error codes in the ZED SDK. More... | |
enum class | MODEL |
Lists ZED camera model. More... | |
enum class | INPUT_TYPE |
Lists available input types in the ZED SDK. More... | |
enum class | CAMERA_STATE |
Lists possible camera states. More... | |
enum class | STREAMING_CODEC |
Lists the different encoding types for image streaming. More... | |
enum class | SENSOR_TYPE |
Lists available sensor types. More... | |
enum class | SENSORS_UNIT |
Lists available measurement units of onboard sensors. More... | |
enum class | BUS_TYPE |
Lists available LIVE input type in the ZED SDK. More... | |
enum class | OBJECT_DETECTION_MODEL |
Lists available models for the object detection module. More... | |
enum class | BODY_TRACKING_MODEL |
Lists available models for the body tracking module. More... | |
enum class | AI_MODELS |
Lists available AI models. More... | |
enum class | MEM |
Lists available memory type. More... | |
enum class | COPY_TYPE |
Lists available copy operation on sl::Mat. More... | |
enum class | MAT_TYPE |
Lists available sl::Mat formats. More... | |
enum class | MODULE |
Lists available modules. More... | |
enum class | OBJECT_CLASS |
Lists available object classes. More... | |
enum class | OBJECT_SUBCLASS |
List available object subclasses. More... | |
enum class | OBJECT_TRACKING_STATE |
Lists the different states of object tracking. More... | |
enum class | OBJECT_ACTION_STATE |
Lists the different states of an object's actions. More... | |
enum class | OBJECT_FILTERING_MODE |
Lists supported bounding box preprocessing. More... | |
enum class | INFERENCE_PRECISION |
Report the actual inference precision used. More... | |
enum class | BODY_FORMAT |
Lists supported skeleton body models. More... | |
enum class | BODY_KEYPOINTS_SELECTION |
Lists supported models for skeleton keypoints selection. More... | |
enum class | REFERENCE_FRAME |
Lists possible types of position matrix used to store camera path and pose. More... | |
enum class | BODY_18_PARTS |
Semantic of human body parts and order of sl::BodyData::keypoint for sl::BODY_FORMAT::BODY_18. More... | |
enum class | BODY_34_PARTS |
Semantic of human body parts and order of sl::BodyData::keypoint for sl::BODY_FORMAT::BODY_34. More... | |
enum class | BODY_38_PARTS |
Semantic of human body parts and order of sl::BodyData::keypoint for sl::BODY_FORMAT::BODY_38. More... | |
enum class | MESH_FILE_FORMAT |
Lists available mesh file formats. More... | |
enum class | MESH_TEXTURE_FORMAT |
Lists available mesh texture formats. More... | |
enum class | PLANE_TYPE |
Lists the available plane types detected based on the orientation. More... | |
enum class | FUSION_ERROR_CODE |
Lists the types of error that can be raised by the Fusion. More... | |
enum class | SENDER_ERROR_CODE |
Lists the types of error that can be raised during the Fusion by senders. More... | |
enum class | POSITION_TYPE |
Lists the types of possible position outputs. More... | |
enum class | GNSS_STATUS |
enum class | GNSS_MODE |
enum class | GNSS_FUSION_STATUS |
Functions | |
* | toString (const FLIP_MODE &flip_mode) |
inline ::std::ostream & | operator<< (::std::ostream &os, const FLIP_MODE &flip_mode) |
sl::Resolution | getResolution (RESOLUTION resolution) |
Gets the corresponding sl::Resolution from an sl::RESOLUTION. More... | |
* | toString (const SVO_COMPRESSION_MODE &svo_compression) |
inline ::std::ostream & | operator<< (::std::ostream &os, const SVO_COMPRESSION_MODE &svo_compression) |
AI_Model_status | checkAIModelStatus (AI_MODELS model, int gpu_id=0) |
Checks if a corresponding optimized engine is found for the requested Model based on your rig configuration. More... | |
ERROR_CODE | downloadAIModel (sl::AI_MODELS model, int gpu_id=0) |
Downloads the requested model. More... | |
ERROR_CODE | optimizeAIModel (sl::AI_MODELS model, int gpu_id=0) |
Optimizes the requested model (and download the model if it is not present on the host). More... | |
* | toString (const SpatialMappingParameters::MAPPING_RESOLUTION &resolution) |
std::ostream & | operator<< (std::ostream &os, const SpatialMappingParameters::MAPPING_RESOLUTION &resolution) |
String | toString (const SpatialMappingParameters::MAPPING_RANGE &range) |
std::ostream & | operator<< (std::ostream &os, const SpatialMappingParameters::MAPPING_RANGE &range) |
String | toString (const SpatialMappingParameters::SPATIAL_MAP_TYPE &map_type) |
std::ostream & | operator<< (std::ostream &os, const SpatialMappingParameters::SPATIAL_MAP_TYPE &map_type) |
String | toVerbose (const ERROR_CODE &errorCode) |
Provide a concise sl::ERROR_CODE string. More... | |
* | str2unit (String unit) |
* | toString (const AI_MODELS &model) |
inline ::std::ostream & | operator<< (::std::ostream &os, const AI_MODELS &model) |
void | sleep_ms (int time) |
Blocks the execution of the current thread for time milliseconds. More... | |
void | sleep_us (int time) |
Blocks the execution of the current thread for time microseconds. More... | |
ERROR_CODE SL_CORE_EXPORT | convertImage (sl::Mat &image_in, sl::Mat &image_signed, cudaStream_t stream=0) |
Convert Image format from Unsigned char to Signed char, designed for Unreal Engine pipeline, works on GPU memory. More... | |
Rotation | computeRotationMatrixFromGravity (sl::float3 axis_to_align, sl::float3 gravity_vector) |
Compute the rotation matrix from the gravity vector : the rotation can used to find the world rotation from the gravity of an IMU. More... | |
Matrix3f | getCoordinateTransformConversion3f (COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst) |
Get the coordinate transform conversion matrix to change coordinate system. More... | |
Matrix4f | getCoordinateTransformConversion4f (COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst) |
Get the coordinate transform conversion matrix to change coordinate system. More... | |
ERROR_CODE | convertCoordinateSystem (Mat &floatMat, COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst, MEM mem=MEM::CPU) |
Change the coordinate system of a matrix. More... | |
ERROR_CODE | convertCoordinateSystem (Transform &motionMat, COORDINATE_SYSTEM coord_system_src, COORDINATE_SYSTEM coord_system_dst) |
Change the coordinate system of a transform matrix. More... | |
float | getUnitScale (UNIT unit_src, UNIT unit_dst) |
Get the unit factor to change units. More... | |
ERROR_CODE | convertUnit (Mat &floatMat, UNIT unit_src, UNIT unit_dst, MEM mem=MEM::CPU) |
Change the unit of a matrix. More... | |
ERROR_CODE | convertUnit (Transform &motionMat, UNIT unit_src, UNIT unit_dst) |
Change the unit (of the translations) of a transform matrix. More... | |
OBJECT_CLASS | getObjectClass (OBJECT_SUBCLASS object_type) |
std::vector< OBJECT_SUBCLASS > | getObjectSubClasses (OBJECT_CLASS object_type) |
String | generate_unique_id () |
Generate a UUID like unique id to help identify and track AI detections. More... | |
int | getIdx (BODY_18_PARTS part) |
Return associated index of each sl::BODY_18_PARTS. More... | |
int | getIdx (BODY_34_PARTS part) |
Return associated index of each sl::BODY_34_PARTS. More... | |
int | getIdx (BODY_38_PARTS part) |
Return associated index of each sl::BODY_38_PARTS. More... | |
* | toString (const MESH_FILE_FORMAT &mesh_frmt) |
std::ostream & | operator<< (std::ostream &os, const MESH_FILE_FORMAT &mesh_frmt) |
* | toString (const MESH_TEXTURE_FORMAT &text_frmt) |
std::ostream & | operator<< (std::ostream &os, const MESH_TEXTURE_FORMAT &text_frmt) |
* | toString (const MeshFilterParameters::MESH_FILTER &mesh_filter) |
std::ostream & | operator<< (std::ostream &os, const MeshFilterParameters::MESH_FILTER &mesh_filter) |
* | toString (const PLANE_TYPE &type) |
std::ostream & | operator<< (std::ostream &os, const PLANE_TYPE &type) |
FusionConfiguration | readFusionConfigurationFile (std::string json_config_filename, int serial_number, sl::COORDINATE_SYSTEM coord_sys, sl::UNIT unit) |
Read a configuration JSON file to configure a fusion process. More... | |
std::vector< FusionConfiguration > | readFusionConfigurationFile (std::string json_config_filename, sl::COORDINATE_SYSTEM coord_sys, sl::UNIT unit) |
Read a Configuration JSON file to configure a fusion process. More... | |
void | writeConfigurationFile (std::string json_config_filename, std::vector< FusionConfiguration > &configuration, sl::COORDINATE_SYSTEM coord_sys, sl::UNIT unit) |
Write a Configuration JSON file to configure a fusion process. More... | |
bool | operator== (const CameraIdentifier &a, const CameraIdentifier &b) |
String | toString (const POSITION_TYPE &position_type) |
inline ::std::ostream & | operator<< (::std::ostream &os, const POSITION_TYPE &position_type) |
Variables | |
static const float | INVALID_VALUE = NAN |
static const unsigned char | STATIC_DEPTH = 255 |
static const unsigned char | DYNAMIC_DEPTH = 127 |
const int | VIDEO_SETTINGS_VALUE_AUTO = -1 |
const std::vector< std::pair< BODY_18_PARTS, BODY_18_PARTS > > | BODY_18_BONES |
Lists links of human body keypoints for sl::BODY_FORMAT::BODY_18. Useful for display. More... | |
const std::vector< std::pair< BODY_34_PARTS, BODY_34_PARTS > > | BODY_34_BONES |
Lists links of human body keypoints for sl::BODY_FORMAT::BODY_34. Useful for display. More... | |
const std::vector< std::pair< BODY_38_PARTS, BODY_38_PARTS > > | BODY_38_BONES |
Lists links of human body keypoints for sl::BODY_FORMAT::BODY_38. Useful for display. More... | |
Unavailable Values | |
static const float | TOO_FAR = INFINITY |
static const float | TOO_CLOSE = -INFINITY |
static const float | OCCLUSION_VALUE = NAN |
Types definition | |
typedef float | float1 |
typedef Vector2< float > | float2 |
typedef Vector3< float > | float3 |
typedef Vector4< float > | float4 |
typedef unsigned char | uchar1 |
typedef Vector2< unsigned char > | uchar2 |
typedef Vector3< unsigned char > | uchar3 |
typedef Vector4< unsigned char > | uchar4 |
typedef double | double1 |
typedef Vector2< double > | double2 |
typedef Vector3< double > | double3 |
typedef Vector4< double > | double4 |
typedef unsigned int | uint1 |
typedef Vector2< unsigned int > | uint2 |
typedef Vector3< unsigned int > | uint3 |
typedef Vector4< unsigned int > | uint4 |
typedef unsigned short | ushort1 |
typedef Vector4< char > | char4 |
bool | operator< (const Timestamp &lhs, const Timestamp &rhs) |
bool | operator> (const Timestamp &lhs, const Timestamp &rhs) |
bool | operator<= (const Timestamp &lhs, const Timestamp &rhs) |
bool | operator>= (const Timestamp &lhs, const Timestamp &rhs) |
bool | operator== (const Timestamp &lhs, const Timestamp &rhs) |
bool | operator!= (const Timestamp &lhs, const Timestamp &rhs) |
Timestamp | operator+ (Timestamp lhs, const Timestamp &rhs) |
Timestamp | operator- (Timestamp lhs, const Timestamp &rhs) |
Timestamp | operator/ (Timestamp lhs, const Timestamp &rhs) |
Timestamp | operator* (Timestamp lhs, const Timestamp &rhs) |
typedef float float1 |
typedef unsigned char uchar1 |
typedef double double1 |
typedef unsigned int uint1 |
typedef unsigned short ushort1 |
|
strong |
|
strong |
|
strong |
|
strong |
|
strong |
* sl::toString | ( | const FLIP_MODE & | flip_mode | ) |
Referenced by operator<<().
inline ::std::ostream& sl::operator<< | ( | ::std::ostream & | os, |
const FLIP_MODE & | flip_mode | ||
) |
* sl::toString | ( | const SVO_COMPRESSION_MODE & | svo_compression | ) |
inline ::std::ostream& sl::operator<< | ( | ::std::ostream & | os, |
const SVO_COMPRESSION_MODE & | svo_compression | ||
) |
* sl::toString | ( | const SpatialMappingParameters::MAPPING_RESOLUTION & | resolution | ) |
|
inline |
String sl::toString | ( | const SpatialMappingParameters::MAPPING_RANGE & | range | ) |
|
inline |
String sl::toString | ( | const SpatialMappingParameters::SPATIAL_MAP_TYPE & | map_type | ) |
|
inline |
* sl::str2unit | ( | String | unit | ) |
* sl::toString | ( | const AI_MODELS & | model | ) |
inline ::std::ostream& sl::operator<< | ( | ::std::ostream & | os, |
const AI_MODELS & | model | ||
) |
ERROR_CODE SL_CORE_EXPORT sl::convertImage | ( | sl::Mat & | image_in, |
sl::Mat & | image_signed, | ||
cudaStream_t | stream = 0 |
||
) |
Convert Image format from Unsigned char to Signed char, designed for Unreal Engine pipeline, works on GPU memory.
image_in | : input image to convert |
image_signed | : output image to converted |
stream | : a cuda stream to put the compute to (def. 0) |
Rotation sl::computeRotationMatrixFromGravity | ( | sl::float3 | axis_to_align, |
sl::float3 | gravity_vector | ||
) |
Compute the rotation matrix from the gravity vector : the rotation can used to find the world rotation from the gravity of an IMU.
axis_to_align | : define the axis to align with the gravity, for instance : to align the "y" axis, axis_to_align = (0, 1, 0)' |
gravity_vector | : the gravity vector, acceleration set by an IMU |
Matrix3f sl::getCoordinateTransformConversion3f | ( | COORDINATE_SYSTEM | coord_system_src, |
COORDINATE_SYSTEM | coord_system_dst | ||
) |
Get the coordinate transform conversion matrix to change coordinate system.
coord_system_src | : the source coordinate system. |
coord_system_dst | : the destination coordinate system. |
Matrix4f sl::getCoordinateTransformConversion4f | ( | COORDINATE_SYSTEM | coord_system_src, |
COORDINATE_SYSTEM | coord_system_dst | ||
) |
Get the coordinate transform conversion matrix to change coordinate system.
coord_system_src | : the source coordinate system. |
coord_system_dst | : the destination coordinate system. |
ERROR_CODE sl::convertCoordinateSystem | ( | Mat & | floatMat, |
COORDINATE_SYSTEM | coord_system_src, | ||
COORDINATE_SYSTEM | coord_system_dst, | ||
MEM | mem = MEM::CPU |
||
) |
Change the coordinate system of a matrix.
floatMat | : (in/out) matrix to transform, can be either a MAT_TYPE::F32_C4 (the fourth value will be ignored as it contained the color information) or a MAT_TYPE::F32_C3. |
coord_system_src | : the current coordinate system of floatMat. |
coord_system_dst | : the destination coordinate system for floatMat. |
mem | : define which memory should be transformed from floatMat. |
ERROR_CODE sl::convertCoordinateSystem | ( | Transform & | motionMat, |
COORDINATE_SYSTEM | coord_system_src, | ||
COORDINATE_SYSTEM | coord_system_dst | ||
) |
Change the coordinate system of a transform matrix.
motionMat | : (in/out) matrix to transform |
coord_system_src | : the current coordinate system of motionMat. |
coord_system_dst | : the destination coordinate system for motionMat. |
Get the unit factor to change units.
unit_src | : the source coordinate system. |
unit_dst | : the destination coordinate system. |
Change the unit of a matrix.
floatMat | : (in/out) matrix to transform, can be either a MAT_TYPE::F32_C4 (the fourth value will be ignored as it contained the color information), MAT_TYPE::F32_C3 or a MAT_TYPE::F32_C1. |
unit_src | : the current unit of floatMat. |
unit_dst | : the destination unit for floatMat. |
mem | : define which memory should be transformed from floatMat. |
ERROR_CODE sl::convertUnit | ( | Transform & | motionMat, |
UNIT | unit_src, | ||
UNIT | unit_dst | ||
) |
Change the unit (of the translations) of a transform matrix.
motionMat | : (in/out) matrix to transform |
unit_src | : the current unit of motionMat. |
unit_dst | : the destination unit for motionMat. |
OBJECT_CLASS sl::getObjectClass | ( | OBJECT_SUBCLASS | object_type | ) |
std::vector<OBJECT_SUBCLASS> sl::getObjectSubClasses | ( | OBJECT_CLASS | object_type | ) |
* sl::toString | ( | const MESH_FILE_FORMAT & | mesh_frmt | ) |
|
inline |
* sl::toString | ( | const MESH_TEXTURE_FORMAT & | text_frmt | ) |
|
inline |
* sl::toString | ( | const MeshFilterParameters::MESH_FILTER & | mesh_filter | ) |
|
inline |
* sl::toString | ( | const PLANE_TYPE & | type | ) |
|
inline |
|
inline |
String sl::toString | ( | const POSITION_TYPE & | position_type | ) |
inline ::std::ostream& sl::operator<< | ( | ::std::ostream & | os, |
const POSITION_TYPE & | position_type | ||
) |
|
static |
Defines an unavailable depth value that is above the depth Max value.
|
static |
Defines an unavailable depth value that is below the depth Min value.
|
static |
Defines an unavailable depth value that is on an occluded image area.
|
static |
|
static |
|
static |
const int VIDEO_SETTINGS_VALUE_AUTO = -1 |