Skip to content

Commit

Permalink
Merge pull request IntelRealSense#5996 from maloel/get_units
Browse files Browse the repository at this point in the history
Added depth_frame::get_units()
  • Loading branch information
dorodnic authored Mar 10, 2020
2 parents 748a043 + 0190928 commit c5a73e1
Show file tree
Hide file tree
Showing 11 changed files with 57 additions and 13 deletions.
6 changes: 6 additions & 0 deletions include/librealsense2/h/rs_frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -150,6 +150,12 @@ int rs2_get_frame_width(const rs2_frame* frame, rs2_error** error);
*/
int rs2_get_frame_height(const rs2_frame* frame, rs2_error** error);

/**
* retrieve the scaling factor to use when converting a depth frame's get_data() units to meters
* \return float - depth, in meters, per 1 unit stored in the frame data
*/
float rs2_depth_frame_get_units( const rs2_frame* frame, rs2_error** error );

/**
* retrieve frame stride in bytes (number of bytes from start of line N to start of line N+1)
* \param[in] frame handle returned from a callback
Expand Down
12 changes: 12 additions & 0 deletions include/librealsense2/hpp/rs_frame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -814,6 +814,18 @@ namespace rs2
error::handle(e);
return r;
}

/**
* Provide the scaling factor to use when converting from get_data() units to meters
* \return float - depth, in meters, per 1 unit stored in the frame data
*/
float get_units() const
{
rs2_error * e = nullptr;
auto r = rs2_depth_frame_get_units( get(), &e );
error::handle( e );
return r;
}
};

class disparity_frame : public depth_frame
Expand Down
8 changes: 8 additions & 0 deletions src/android/jni/frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -130,6 +130,14 @@ Java_com_intel_realsense_librealsense_DepthFrame_nGetDistance(JNIEnv *env, jclas
return rv;
}

extern "C" JNIEXPORT jfloat JNICALL
Java_com_intel_realsense_librealsense_DepthFrame_nGetUnits( JNIEnv *env, jclass type, jlong handle ) {
rs2_error *e = NULL;
float rv = rs2_depth_frame_get_units( reinterpret_cast<const rs2_frame *>(handle), &e );
handle_error( env, e );
return rv;
}

extern "C" JNIEXPORT jint JNICALL
Java_com_intel_realsense_librealsense_Points_nGetCount(JNIEnv *env, jclass type, jlong handle) {
rs2_error *e = NULL;
Expand Down
1 change: 1 addition & 0 deletions src/realsense.def
Original file line number Diff line number Diff line change
Expand Up @@ -195,6 +195,7 @@ EXPORTS
rs2_embedded_frames_count
rs2_extract_frame
rs2_depth_frame_get_distance
rs2_depth_frame_get_units
rs2_depth_stereo_frame_get_baseline
rs2_get_stereo_baseline

Expand Down
8 changes: 8 additions & 0 deletions src/rs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2160,6 +2160,14 @@ float rs2_depth_frame_get_distance(const rs2_frame* frame_ref, int x, int y, rs2
}
HANDLE_EXCEPTIONS_AND_RETURN(0, frame_ref, x, y)

float rs2_depth_frame_get_units( const rs2_frame* frame_ref, rs2_error** error ) BEGIN_API_CALL
{
VALIDATE_NOT_NULL( frame_ref );
auto df = VALIDATE_INTERFACE((( frame_interface * ) frame_ref ), librealsense::depth_frame );
return df->get_units();
}
HANDLE_EXCEPTIONS_AND_RETURN( 0, frame_ref )

float rs2_depth_stereo_frame_get_baseline(const rs2_frame* frame_ref, rs2_error** error) BEGIN_API_CALL
{
VALIDATE_NOT_NULL(frame_ref);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,5 +10,10 @@ public float getDistance(int x, int y) {
return nGetDistance(mHandle, x, y);
}

public float getUnits() {
return nGetUnits(mHandle);
}

private static native float nGetDistance(long handle, int x, int y);
private static native float nGetUnits(long handle);
}
7 changes: 7 additions & 0 deletions wrappers/csharp/Intel.RealSense/Frames/DepthFrame.cs
Original file line number Diff line number Diff line change
Expand Up @@ -21,5 +21,12 @@ public float GetDistance(int x, int y)
object error;
return NativeMethods.rs2_depth_frame_get_distance(Handle, x, y, out error);
}
/// <summary>Provide the scaling factor to use when converting from frame data units to meters</summary>
/// <returns>Depth, in meters, per 1 unit stored in the frame data</returns>
public float GetUnits()
{
object error;
return NativeMethods.rs2_depth_frame_get_units(Handle, out error);
}
}
}
3 changes: 3 additions & 0 deletions wrappers/csharp/Intel.RealSense/NativeMethods.cs
Original file line number Diff line number Diff line change
Expand Up @@ -568,6 +568,9 @@ internal static MemCpyDelegate GetMethod()
[DllImport(dllName, CallingConvention = CallingConvention.Cdecl)]
internal static extern float rs2_depth_frame_get_distance(IntPtr frame_ref, int x, int y, [MarshalAs(UnmanagedType.CustomMarshaler, MarshalTypeRef = typeof(ErrorMarshaler))] out object error);

[DllImport(dllName, CallingConvention = CallingConvention.Cdecl)]
internal static extern float rs2_depth_frame_get_units(IntPtr frame_ref, [MarshalAs(UnmanagedType.CustomMarshaler, MarshalTypeRef = typeof(ErrorMarshaler))] out object error);

[DllImport(dllName, CallingConvention = CallingConvention.Cdecl)]
internal static extern float rs2_depth_stereo_frame_get_baseline(IntPtr frame_ref, [MarshalAs(UnmanagedType.CustomMarshaler, MarshalTypeRef = typeof(ErrorMarshaler))] out object error);

Expand Down
15 changes: 4 additions & 11 deletions wrappers/opencv/cv-helpers.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,18 +45,11 @@ cv::Mat frame_to_mat(const rs2::frame& f)
}

// Converts depth frame to a matrix of doubles with distances in meters
cv::Mat depth_frame_to_meters(const rs2::pipeline& pipe, const rs2::depth_frame& f)
cv::Mat depth_frame_to_meters( const rs2::depth_frame & f )
{
using namespace cv;
using namespace rs2;

Mat dm = frame_to_mat(f);
dm.convertTo(dm, CV_64F);
auto depth_scale = pipe.get_active_profile()
.get_device()
.first<depth_sensor>()
.get_depth_scale();
dm = dm * depth_scale;
cv::Mat dm = frame_to_mat(f);
dm.convertTo( dm, CV_64F );
dm = dm * f.get_units();
return dm;
}

2 changes: 1 addition & 1 deletion wrappers/opencv/dnn/rs-dnn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,7 +71,7 @@ int main(int argc, char** argv) try

// Convert RealSense frame to OpenCV matrix:
auto color_mat = frame_to_mat(color_frame);
auto depth_mat = depth_frame_to_meters(pipe, depth_frame);
auto depth_mat = depth_frame_to_meters(depth_frame);

Mat inputBlob = blobFromImage(color_mat, inScaleFactor,
Size(inWidth, inHeight), meanVal, false); //Convert Mat to batch of images
Expand Down
3 changes: 2 additions & 1 deletion wrappers/python/pyrs_frame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -207,7 +207,8 @@ void init_frame(py::module &m) {

py::class_<rs2::depth_frame, rs2::video_frame> depth_frame(m, "depth_frame", "Extends the video_frame class with additional depth related attributes and functions.");
depth_frame.def(py::init<rs2::frame>())
.def("get_distance", &rs2::depth_frame::get_distance, "x"_a, "y"_a, "Provide the depth in meters at the given pixel");
.def("get_distance", &rs2::depth_frame::get_distance, "x"_a, "y"_a, "Provide the depth in meters at the given pixel")
.def("get_units", &rs2::depth_frame::get_units, "Provide the scaling factor to use when converting from get_data() units to meters");

// rs2::disparity_frame
py::class_<rs2::disparity_frame, rs2::depth_frame> disparity_frame(m, "disparity_frame", "Extends the depth_frame class with additional disparity related attributes and functions.");
Expand Down

0 comments on commit c5a73e1

Please sign in to comment.