1 package com.intel.realsense.librealsense;
21 if(mTextureCoordinates == null){
22 mTextureCoordinates =
new float[
getCount() * 2];
45 private static native
void nGetData(
long handle,
float[]
data);
47 private static native
void nExportToPly(
long handle,
String filePath,
long textureHandle);
static native void nGetTextureCoordinates(long handle, float[] data)
uvc_xu_option< int > super
GLuint64 GLenum void * handle
::std_msgs::String_< std::allocator< void > > String
static native void nExportToPly(long handle, String filePath, long textureHandle)
void getData(float[] data)
float[] mTextureCoordinates
void getTextureCoordinates(float[] data)
void exportToPly(String filePath, VideoFrame texture)
float[] getTextureCoordinates()
static native int nGetCount(long handle)
static native void nGetData(long handle, float[] data)