Go to the documentation of this file.
2 package com.introlab.rtabmap;
3 import java.nio.ByteBuffer;
4 import java.nio.FloatBuffer;
6 import android.app.Activity;
7 import android.content.Context;
8 import android.os.IBinder;
9 import android.view.KeyEvent;
10 import android.util.Log;
23 Log.w(
RTABMapActivity.class.getSimpleName(),
"WArning! Unable to load libtango_client_api.so! This can be safely ignored if RTAB-Map NDK is not build with tango support.");
25 System.loadLibrary(
"NativeRTABMap");
37 public static native int openDatabase(
long nativeApplication, String databasePath,
boolean databaseInMemory,
boolean optimize,
boolean clearDatabase);
39 public static native boolean recover(
long nativeApplication, String from, String to);
41 public static native boolean isBuiltWith(
long nativeApplication,
int cameraDriver);
42 public static native boolean startCamera(
long nativeApplication, IBinder binder, Context context, Activity activity,
int driver);
56 public static native void setCamera(
long nativeApplication,
int cameraIndex);
59 public static native void onTouchEvent(
long nativeApplication,
int touchCount,
int event0,
60 float x0,
float y0,
float x1,
float y1);
98 long nativeApplication,
107 public static native void save(
long nativeApplication, String outputDatabasePath);
110 long nativeApplication,
111 float cloudVoxelSize,
112 boolean regenerateCloud,
118 float optimizedVoxelSize,
120 int optimizedMaxPolygons,
121 float optimizedColorRadius,
122 boolean optimizedCleanWhitePolygons,
123 int optimizedMinClusterSize,
124 float optimizedMaxTextureDistance,
125 int optimizedMinTextureClusterSize,
126 boolean blockRendering);
138 public static native void postCameraPoseEvent(
long nativeApplication,
float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw,
double stamp);
140 float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw,
141 float rgb_fx,
float rgb_fy,
float rgb_cx,
float rgb_cy,
142 float rgbFrameX,
float rgbFrameY,
float rgbFrameZ,
float rgbFrameQX,
float rgbFrameQY,
float rgbFrameQZ,
float rgbFrameQW,
144 ByteBuffer yPlane, ByteBuffer uPlane, ByteBuffer vPlane,
int yPlaneLen,
int rgbWidth,
int rgbHeight,
int rgbFormat,
145 FloatBuffer points,
int pointsLen,
146 float vx,
float vy,
float vz,
float vqx,
float vqy,
float vqz,
float vqw,
147 float p00,
float p11,
float p02,
float p12,
float p22,
float p32,
float p23,
148 float t0,
float t1,
float t2,
float t3,
float t4,
float t5,
float t6,
float t7);
150 float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw,
151 float rgb_fx,
float rgb_fy,
float rgb_cx,
float rgb_cy,
152 float depth_fx,
float depth_fy,
float depth_cx,
float depth_cy,
153 float rgbFrameX,
float rgbFrameY,
float rgbFrameZ,
float rgbFrameQX,
float rgbFrameQY,
float rgbFrameQZ,
float rgbFrameQW,
154 float depthFrameX,
float depthFrameY,
float depthFrameZ,
float depthFrameQX,
float depthFrameQY,
float depthFrameQZ,
float depthFrameQW,
157 ByteBuffer yPlane, ByteBuffer uPlane, ByteBuffer vPlane,
int yPlaneLen,
int rgbWidth,
int rgbHeight,
int rgbFormat,
158 ByteBuffer depth,
int depthLen,
int depthWidth,
int depthHeight,
int depthFormat,
159 FloatBuffer points,
int pointsLen,
160 float vx,
float vy,
float vz,
float vqx,
float vqy,
float vqz,
float vqw,
161 float p00,
float p11,
float p02,
float p12,
float p22,
float p32,
float p23,
162 float t0,
float t1,
float t2,
float t3,
float t4,
float t5,
float t6,
float t7);
static native int postProcessing(long nativeApplication, int approach)
static native void setOnlineBlending(long nativeApplication, boolean enabled)
static native void setOrthoCropFactor(long nativeApplication, float value)
static native void setTrajectoryMode(long nativeApplication, boolean enabled)
static native void setLighting(long nativeApplication, boolean enabled)
static native long createNativeApplication(RTABMapActivity activity)
static native void setMeshTriangleSize(long nativeApplication, int value)
static native void setDataRecorderMode(long nativeApplication, boolean enabled)
static native void setGridVisible(long nativeApplication, boolean visible)
static native void setBackfaceCulling(long nativeApplication, boolean enabled)
static native void setCamera(long nativeApplication, int cameraIndex)
static native void setMinCloudDepth(long nativeApplication, float value)
static native int setMappingParameter(long nativeApplication, String key, String value)
static native void setAppendMode(long nativeApplication, boolean enabled)
static native void setLocalizationMode(long nativeApplication, boolean enabled)
static native void setNodesFiltering(long nativeApplication, boolean enabled)
static native void setMaxCloudDepth(long nativeApplication, float value)
static native void postOdometryEventDepth(long nativeApplication, float x, float y, float z, float qx, float qy, float qz, float qw, float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy, float depth_fx, float depth_fy, float depth_cx, float depth_cy, float rgbFrameX, float rgbFrameY, float rgbFrameZ, float rgbFrameQX, float rgbFrameQY, float rgbFrameQZ, float rgbFrameQW, float depthFrameX, float depthFrameY, float depthFrameZ, float depthFrameQX, float depthFrameQY, float depthFrameQZ, float depthFrameQW, double rgbStamp, double depthStamp, ByteBuffer yPlane, ByteBuffer uPlane, ByteBuffer vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, ByteBuffer depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, FloatBuffer points, int pointsLen, float vx, float vy, float vz, float vqx, float vqy, float vqz, float vqw, float p00, float p11, float p02, float p12, float p22, float p32, float p23, float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7)
static native void setGridRotation(long nativeApplication, float value)
static native void setGPS(long nativeApplication, double stamp, double longitude, double latitude, double altitude, double accuracy, double bearing)
static native boolean writeExportedMesh(long nativeApplication, String directory, String name)
static native void addEnvSensor(long nativeApplication, int type, float value)
static native void stopCamera(long nativeApplication)
gtsam.ISAM2 optimize(List[GpsMeasurement] gps_measurements, List[ImuMeasurement] imu_measurements, gtsam.noiseModel.Diagonal sigma_init_x, gtsam.noiseModel.Diagonal sigma_init_v, gtsam.noiseModel.Diagonal sigma_init_b, gtsam.noiseModel.Diagonal noise_model_gps, KittiCalibration kitti_calibration, int first_gps_pose, int gps_skip)
static native void setRenderingTextureDecimation(long nativeApplication, int value)
static native void onTouchEvent(long nativeApplication, int touchCount, int event0, float x0, float y0, float x1, float y1)
static native void setSmoothing(long nativeApplication, boolean enabled)
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
static native void setCloudDensityLevel(long nativeApplication, int value)
static native void setMeshRendering(long nativeApplication, boolean enabled, boolean withTexture)
static native int getTotalNodes(long nativeApplication)
static native void setRawScanSaved(long nativeApplication, boolean enabled)
static native boolean exportMesh(long nativeApplication, float cloudVoxelSize, boolean regenerateCloud, boolean meshing, int textureSize, int textureCount, int normalK, boolean optimized, float optimizedVoxelSize, int optimizedDepth, int optimizedMaxPolygons, float optimizedColorRadius, boolean optimizedCleanWhitePolygons, int optimizedMinClusterSize, float optimizedMaxTextureDistance, int optimizedMinTextureClusterSize, boolean blockRendering)
static native int getTotalWords(long nativeApplication)
static native void setMeshAngleTolerance(long nativeApplication, float value)
static native void initGlContent(long nativeApplication)
static native boolean isBuiltWith(long nativeApplication, int cameraDriver)
static native int getTotalPoints(long nativeApplication)
static native boolean recover(long nativeApplication, String from, String to)
static native boolean postExportation(long nativeApplication, boolean visualize)
const gtsam::Symbol key( 'X', 0)
static native void setupGraphic(long nativeApplication, int width, int height)
static native void setGraphOptimization(long nativeApplication, boolean enabled)
CEPHES_EXTERN_EXPORT double y1(double x)
static final int loadTangoSharedLibrary()
RTABMapApp * native(jlong ptr)
static native String getStatus(long nativeApplication)
static native void setMapCloudShown(long nativeApplication, boolean shown)
static final int ARCH_ERROR
CEPHES_EXTERN_EXPORT double y0(double x)
static native void setCameraColor(long nativeApplication, boolean enabled)
static native void cancelProcessing(long nativeApplication)
static native void setOdomCloudShown(long nativeApplication, boolean shown)
static native int getLoopClosureId(long nativeApplication)
static native void setScreenRotation(long nativeApplication, int displayRotation, int cameraRotation)
static native boolean startCamera(long nativeApplication, IBinder binder, Context context, Activity activity, int driver)
static native void setBackgroundColor(long nativeApplication, float gray)
static native void setPointSize(long nativeApplication, float value)
static native void save(long nativeApplication, String outputDatabasePath)
static native void postCameraPoseEvent(long nativeApplication, float x, float y, float z, float qx, float qy, float qz, float qw, double stamp)
static native void postOdometryEvent(long nativeApplication, float x, float y, float z, float qx, float qy, float qz, float qw, float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy, float rgbFrameX, float rgbFrameY, float rgbFrameZ, float rgbFrameQX, float rgbFrameQY, float rgbFrameQZ, float rgbFrameQW, double stamp, ByteBuffer yPlane, ByteBuffer uPlane, ByteBuffer vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, FloatBuffer points, int pointsLen, float vx, float vy, float vz, float vqx, float vqy, float vqz, float vqw, float p00, float p11, float p02, float p12, float p22, float p32, float p23, float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7)
static native void setFullResolution(long nativeApplication, boolean enabled)
static native void setWireframe(long nativeApplication, boolean enabled)
static native void setGraphVisible(long nativeApplication, boolean visible)
static native void setClusterRatio(long nativeApplication, float value)
static native float getUpdateTime(long nativeApplication)
static native void setDepthFromMotion(long nativeApplication, boolean enabled)
static native int openDatabase(long nativeApplication, String databasePath, boolean databaseInMemory, boolean optimize, boolean clearDatabase)
static native void setMaxGainRadius(long nativeApplication, float value)
static native void destroyNativeApplication(long nativeApplication)
static native int render(long nativeApplication)
static native void setFOV(long nativeApplication, float value)
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
static native void setPausedMapping(long nativeApplication, boolean paused)
rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:15