1 package com.intel.realsense.librealsense;
3 public class Config extends LrsClass {
50 long pipeHandle =
nResolve(mHandle, pipeline.mHandle);
60 private static native
long nCreate();
69 private static native
boolean nCanResolve(
long handle,
long pipelineHandle);
70 private static native
long nResolve(
long handle,
long pipelineHandle);
void enableStream(StreamType type, int width, int height, StreamFormat format)
void enableRecordToFile(String filePath)
static native void nDisableAllStreams(long handle)
static native void nEnableStream(long handle, int type, int index, int width, int height, int format, int framerate)
static native void nDisableStream(long handle, int type)
void enableDeviceFromFile(String filePath)
::std_msgs::String_< std::allocator< void > > String
void enableStream(StreamType type, int width, int height)
GLint GLsizei GLsizei height
GLint GLint GLsizei GLint GLenum format
static native boolean nCanResolve(long handle, long pipelineHandle)
static native void nEnableDeviceFromFile(long handle, String filePath)
void enableStream(StreamType type)
void enableStream(StreamType type, int index, int width, int height, StreamFormat format, int framerate)
static native long nResolve(long handle, long pipelineHandle)
void enableDevice(String serial)
void enableStream(StreamType type, StreamFormat format)
boolean canResolve(Pipeline pipeline)
static native long nCreate()
void disableStream(StreamType type)
static native void nEnableRecordToFile(long handle, String filePath)
static native void nDelete(long handle)
static native void nEnableAllStreams(long handle)
void resolve(Pipeline pipeline)
static native void nEnableDevice(long handle, String serial)