Skip to content

Commit

Permalink
update to 4.0.5 (#26)
Browse files Browse the repository at this point in the history
  • Loading branch information
Bvallon-sl authored Jul 5, 2023
1 parent e34b26f commit 1817bd7
Show file tree
Hide file tree
Showing 10 changed files with 296 additions and 237 deletions.
Binary file modified Content/ZED/Levels/L_BodyTrackingSingle.umap
Binary file not shown.
Binary file modified Content/ZED/Levels/L_Passthrough.umap
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -260,6 +260,7 @@ void USlCameraProxy::Internal_OpenCamera(const FSlInitParameters& InitParameters
sl_init_parameters.svo_real_time_mode = InitParameters.bRealTime;
sl_init_parameters.async_grab_camera_recovery = InitParameters.bAsyncGrabCameraRecovery;
sl_init_parameters.open_timeout_sec = InitParameters.OpenTimeoutSec;
sl_init_parameters.grab_compute_capping_fps = InitParameters.GrabComputeCappingFPS;

InputType = (SL_INPUT_TYPE)InitParameters.InputType;
bool IsCameraCreated = sl_create_camera(CameraID);
Expand Down Expand Up @@ -1562,10 +1563,10 @@ int USlCameraProxy::GetNumberOfKeypoints()
{
return 38;
}
else if (BodyTrackingParameters.BodyFormat == ESlBodyFormat::BF_BODY_70)
/*else if (BodyTrackingParameters.BodyFormat == ESlBodyFormat::BF_BODY_70)
{
return 70;
}
}*/
else
{
return 38;
Expand All @@ -1586,10 +1587,10 @@ int USlCameraProxy::GetNumberOfBones()
{
return 37;
}
else if (BodyTrackingParameters.BodyFormat == ESlBodyFormat::BF_BODY_70)
/*else if (BodyTrackingParameters.BodyFormat == ESlBodyFormat::BF_BODY_70)
{
return 69;
}
}*/
else
{
return 37;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -597,7 +597,7 @@ enum class ESlBodyFormat : uint8
BF_BODY_18 UMETA(DisplayName = "Body 18"),
BF_BODY_34 UMETA(DisplayName = "Body 34"),
BF_BODY_38 UMETA(DisplayName = "Body 38"),
BF_BODY_70 UMETA(DisplayName = "Body 70")
// BF_BODY_70 UMETA(DisplayName = "Body 70")
};

/*
Expand Down Expand Up @@ -784,6 +784,7 @@ enum class ESlBody38Parts : uint8 {
LAST = 38
};

#if 0
/*
* List of human body parts and order of SlBodyData::keypoint for BODY_FORMAT::BODY_70.
*/
Expand Down Expand Up @@ -865,6 +866,7 @@ enum class ESlBody70Parts : uint8 {
LAST = 70
};

#endif

/************************************************************************/
/* Structs */
Expand Down Expand Up @@ -952,6 +954,8 @@ struct STEREOLABS_API FSlBody38Bone
ESlBody38Parts SecondEnd;
};

#if 0

/*
* Bone descriptor, pair of ESlBodyPartsPose70
* To be used in the correspondance array in ZEDPlayerController
Expand Down Expand Up @@ -979,6 +983,8 @@ struct STEREOLABS_API FSlBody70Bone
ESlBody70Parts SecondEnd;
};

#endif

/*
* SDK device properties
* see sl::DeviceProperties
Expand Down Expand Up @@ -2246,8 +2252,9 @@ struct STEREOLABS_API FSlInitParameters
bSensorsRequired(false),
bEnableImageEnhancement(true),
OpenTimeoutSec(5.0f),
bAsyncGrabCameraRecovery(false),
VerboseFilePath(""),
bAsyncGrabCameraRecovery(false)
GrabComputeCappingFPS(0.0f)
{
}

Expand Down Expand Up @@ -2420,6 +2427,13 @@ struct STEREOLABS_API FSlInitParameters
*Path
);
bLoop = bConfigLoop;

GConfig->GetFloat(
Section,
TEXT("GrabComputeCappingFPS"),
GrabComputeCappingFPS,
*Path
);
}

FORCEINLINE void Save(const FString& Path) const
Expand Down Expand Up @@ -2577,6 +2591,13 @@ struct STEREOLABS_API FSlInitParameters
bLoop,
*Path
);

GConfig->SetFloat(
Section,
TEXT("GrabComputeCappingFPS"),
GrabComputeCappingFPS,
*Path
);
}

/** Input type used in the ZED SDK */
Expand Down Expand Up @@ -2694,6 +2715,17 @@ struct STEREOLABS_API FSlInitParameters
/** Verbose file path */
UPROPERTY(EditAnywhere, BlueprintReadWrite)
FString VerboseFilePath;

/**
Define a computation upper limit to the grab frequency.
This can be useful to get a known constant fixed rate or limit the computation load while keeping a short exposure time by setting a high camera capture framerate.
\n The value should be inferior to the InitParameters::camera_fps and strictly positive. It has no effect when reading an SVO file.
\n This is an upper limit and won't make a difference if the computation is slower than the desired compute capping fps.
\note Internally the grab function always tries to get the latest available image while respecting the desired fps as much as possible.
default is 0.
*/
UPROPERTY(EditAnywhere, BlueprintReadWrite)
float GrabComputeCappingFPS;
};

/*
Expand Down Expand Up @@ -3014,12 +3046,12 @@ struct STEREOLABS_API FSlBodyTrackingParameters
bEnableTracking(true),
bEnableSegmentation(false),
DetectionModel(ESlBodyTrackingModel::BTM_HumanBodyMedium),
bEnableBodyFitting(true),
BodyFormat(ESlBodyFormat::BF_BODY_38),
BodySelection(ESlBodyKeypointsSelection::BKS_FULL),
MaxRange(-1.0f),
PredictionTimeout_s(0.2f),
bAllowReducedPrecisionInference(false),
BodySelection(ESlBodyKeypointsSelection::BKS_FULL),
BodyFormat(ESlBodyFormat::BF_BODY_38),
bEnableBodyFitting(true)
bAllowReducedPrecisionInference(false)
{}
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1829,10 +1829,10 @@ namespace sl
{
NbKP = 38;
}
else if (BodyFormat == ESlBodyFormat::BF_BODY_70)
/*else if (BodyFormat == ESlBodyFormat::BF_BODY_70)
{
NbKP = 70;
}
}*/

for (int i = 0; i < NbKP; i++)
{
Expand Down Expand Up @@ -2126,6 +2126,7 @@ namespace sl
InitParameters.sdk_gpu_id = FMath::FloorToInt(UnrealData.GPUID);
InitParameters.sdk_verbose = UnrealData.bVerbose;
InitParameters.sdk_verbose_log_file = TCHAR_TO_UTF8(*UnrealData.VerboseFilePath);
InitParameters.grab_compute_capping_fps = UnrealData.GrabComputeCappingFPS;
if (UnrealData.InputType == ESlInputType::IT_SVO)
{
InitParameters.input.setFromSVOFile(TCHAR_TO_UTF8(*UnrealData.SvoPath));
Expand Down Expand Up @@ -2400,14 +2401,14 @@ namespace sl
case SL_BODY_TRACKING_MODEL_HUMAN_BODY_FAST: m_out = SL_AI_MODELS_HUMAN_BODY_38_FAST_DETECTION; break;
}
}
else if (body_format == SL_BODY_FORMAT_BODY_70)
/*else if (body_format == SL_BODY_FORMAT_BODY_70)
{
switch (m_in) {
case SL_BODY_TRACKING_MODEL_HUMAN_BODY_ACCURATE: m_out = SL_AI_MODELS_HUMAN_BODY_70_ACCURATE_DETECTION; break;
case SL_BODY_TRACKING_MODEL_HUMAN_BODY_MEDIUM: m_out = SL_AI_MODELS_HUMAN_BODY_70_MEDIUM_DETECTION; break;
case SL_BODY_TRACKING_MODEL_HUMAN_BODY_FAST: m_out = SL_AI_MODELS_HUMAN_BODY_70_FAST_DETECTION; break;
}
}
}*/
else
{
switch (m_in) {
Expand Down
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -218,7 +218,7 @@ struct USB_product {
\brief Lists error codes in the ZED SDK.
*/
enum SL_ERROR_CODE {
SL_ERROR_CODE_CAMERA_REBOOTING = -1,
SL_ERROR_CODE_CAMERA_REBOOTING = -1, /**< The ZED camera is currently rebooting.*/
SL_ERROR_CODE_SUCCESS, /**< Standard code for successful behavior.*/
SL_ERROR_CODE_FAILURE, /**< Standard code for unsuccessful behavior.*/
SL_ERROR_CODE_NO_GPU_COMPATIBLE, /**< No GPU found or CUDA capability of the device is not supported.*/
Expand All @@ -241,10 +241,10 @@ enum SL_ERROR_CODE {
SL_ERROR_CODE_CAMERA_NOT_INITIALIZED, /**< In grab() only, ZED SDK is not initialized. Probably a missing call to SL_Camera::open.*/
SL_ERROR_CODE_NVIDIA_DRIVER_OUT_OF_DATE, /**< Your NVIDIA driver is too old and not compatible with your current CUDA version. */
SL_ERROR_CODE_INVALID_FUNCTION_CALL, /**< The call of the function is not valid in the current context. Could be a missing call of SL_Camera::open. */
SL_ERROR_CODE_CORRUPTED_SDK_INSTALLATION, /**< The SDK wasn't able to load its dependencies or somes assets are missing, the installer should be launched. */
SL_ERROR_CODE_CORRUPTED_SDK_INSTALLATION, /**< The SDK wasn't able to load its dependencies or some assets are missing, the installer should be launched. */
SL_ERROR_CODE_INCOMPATIBLE_SDK_VERSION, /**< The installed SDK is incompatible SDK used to compile the program. */
SL_ERROR_CODE_INVALID_AREA_FILE, /**< The given area file does not exist, check the path. */
SL_ERROR_CODE_INCOMPATIBLE_AREA_FILE, /**< The area file does not contain enought data to be used or the SL_DEPTH_MODE used during the creation of the area file is different from the one currently set. */
SL_ERROR_CODE_INCOMPATIBLE_AREA_FILE, /**< The area file does not contain enough data to be used or the SL_DEPTH_MODE used during the creation of the area file is different from the one currently set. */
SL_ERROR_CODE_CAMERA_FAILED_TO_SETUP, /**< Failed to open the camera at the proper resolution. Try another resolution or make sure that the UVC driver is properly installed.*/
SL_ERROR_CODE_CAMERA_DETECTION_ISSUE, /**< Your ZED can not be opened, try replugging it to another USB port or flipping the USB-C connector.*/
SL_ERROR_CODE_CANNOT_START_CAMERA_STREAM, /**< Cannot start camera stream. Make sure your camera is not already used by another process or blocked by firewall or antivirus.*/
Expand Down Expand Up @@ -679,9 +679,9 @@ enum SL_AI_MODELS {
SL_AI_MODELS_HUMAN_BODY_38_FAST_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_FAST
SL_AI_MODELS_HUMAN_BODY_38_MEDIUM_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_FAST
SL_AI_MODELS_HUMAN_BODY_38_ACCURATE_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_FAST
SL_AI_MODELS_HUMAN_BODY_70_FAST_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_FAST
SL_AI_MODELS_HUMAN_BODY_70_MEDIUM_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_FAST
SL_AI_MODELS_HUMAN_BODY_70_ACCURATE_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_FAST
SL_AI_MODELS_HUMAN_BODY_70_FAST_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_FAST.
SL_AI_MODELS_HUMAN_BODY_70_MEDIUM_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_MEDIUM
SL_AI_MODELS_HUMAN_BODY_70_ACCURATE_DETECTION, // related to sl::DETECTION_MODEL::HUMAN_BODY_ACCURATE
SL_AI_MODELS_PERSON_HEAD_DETECTION, // related to sl::DETECTION_MODEL::PERSON_HEAD_BOX
SL_AI_MODELS_PERSON_HEAD_ACCURATE_DETECTION, // related to sl::DETECTION_MODEL::PERSON_HEAD_BOX_ACCURATE
SL_AI_MODELS_REID_ASSOCIATION, // related to sl::BatchParameters::enable
Expand Down Expand Up @@ -729,11 +729,13 @@ enum SL_BODY_FORMAT
*/
SL_BODY_FORMAT_BODY_38,

#if 0
/**
* \brief 70 keypoint model.
* Body model, including feet and full hands models (and simplified face)
*/
SL_BODY_FORMAT_BODY_70,
#endif
};

enum SL_BODY_KEYPOINTS_SELECTION
Expand Down Expand Up @@ -870,6 +872,7 @@ enum SL_BODY_38_PARTS
SL_BODY_38_PARTS_LAST
};

#if 0
/**
* \brief semantic of human body parts and order of \ref ObjectData::keypoint for BODY_FORMAT::BODY_70.
*/
Expand Down Expand Up @@ -950,6 +953,7 @@ enum SL_BODY_70_PARTS
SL_BODY_70_PARTS_RIGHT_HAND_PINKY_4,
SL_BODY_70_PARTS_LAST
};
#endif

/**
\brief Change the type of outputed position for the Fusion positional tracking (raw data or fusion data projected into zed camera)
Expand Down Expand Up @@ -1139,6 +1143,16 @@ struct SL_InitParameters
The default behavior is synchronous, like previous ZED SDK versions
*/
bool async_grab_camera_recovery;
/**
Define a computation upper limit to the grab frequency.
This can be useful to get a known constant fixed rate or limit the computation load while keeping a short exposure time by setting a high camera capture framerate.
\n The value should be inferior to the InitParameters::camera_fps and strictly positive. It has no effect when reading an SVO file.
\n This is an upper limit and won't make a difference if the computation is slower than the desired compute capping fps.
\note Internally the grab function always tries to get the latest available image while respecting the desired fps as much as possible.
default is 0.
*/
float grab_compute_capping_fps;

};

/**
Expand Down Expand Up @@ -2154,36 +2168,36 @@ struct SL_BodyData
* Expressed in pixels on the original image resolution, [0,0] is the top left corner.
\warning in some cases, eg. body partially out of the image, some keypoint can not be detected, they will have negatives coordinates.
*/
struct SL_Vector2 keypoint_2d[70];
struct SL_Vector2 keypoint_2d[38];
/**
* \brief A set of useful points representing the human body, expressed in 3D.
* We use a classic 18 points representation, the points semantic and order is given by BODY_PARTS.
* Defined in \ref sl:InitParameters::UNIT, expressed in \ref RuntimeParameters::measure3D_reference_frame.
\warning in some cases, eg. body partially out of the image or missing depth data, some keypoint can not be detected, they will have non finite values.
*/
struct SL_Vector3 keypoint[70];
struct SL_Vector3 keypoint[38];

/**
* \brief Per keypoint detection confidence, can not be lower than the \ref ObjectDetectionRuntimeParameters::detection_confidence_threshold.
\warning in some cases, eg. body partially out of the image or missing depth data, some keypoint can not be detected, they will have non finite values.
*/
float keypoint_confidence[70];
float keypoint_confidence[38];
/**
* \brief Per keypoint detection 3d covariance
\warning in some cases, eg. body partially out of the image or missing depth data, some keypoint can not be detected, they covariance will be 0.
see \ref position_covariance for the storage format
*/
float keypoint_covariances[70][6];
float keypoint_covariances[38][6];
/**
\brief Per keypoint local position (the position of the child keypoint with respect to its parent expressed in its parent coordinate frame)
\note it is expressed in sl::REFERENCE_CAMERA or sl::REFERENCE_WORLD
*/
struct SL_Vector3 local_position_per_joint[70];
struct SL_Vector3 local_position_per_joint[38];
/**
\brief Per keypoint local orientation
\note the orientation is represented by a quaternion which is stored in sl::float4 (sl::float4 q = sl::float4(qx,qy,qz,qw);)
*/
struct SL_Quaternion local_orientation_per_joint[70];
struct SL_Quaternion local_orientation_per_joint[38];
/**
\brief global root orientation of the skeleton. The orientation is also represented by a quaternion with the same format as \ref local_orientation_per_joint
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -122,16 +122,16 @@ void FAnimNode_ZEDPose::BuildPoseFromSlBodyData(FPoseContext& PoseContext)
KeypointsMirrored = Keypoints38Mirrored;
ParentsIdx = parents38Idx;
}
else if (BodyData.Keypoint.Num() == Keypoints70.Num())
/*else if (BodyData.Keypoint.Num() == Keypoints70.Num())
{
NbKeypoints = 70;
Keypoints = Keypoints70;
KeypointsMirrored = Keypoints70Mirrored;
ParentsIdx = parents70Idx;
}
}*/
else
{
UE_LOG(LogTemp, Warning, TEXT("Incompatible body format, please use either body 34/38 or 70"));
UE_LOG(LogTemp, Warning, TEXT("Incompatible body format, please use either body 34 or 38 "));
}
}

Expand Down Expand Up @@ -167,7 +167,7 @@ void FAnimNode_ZEDPose::BuildPoseFromSlBodyData(FPoseContext& PoseContext)
RightFootPosition = SkeletalMesh->GetBoneLocation(RemapAsset[Keypoints[24]]) + RightAnkleToHeelOffset;

}
else // body 38 or 70
else // body 38
{
if (LeftAnkleToHeelOffset == 0 && RightAnkleToHeelOffset == 0)
{
Expand Down
Loading

0 comments on commit 1817bd7

Please sign in to comment.