Go to the source code of this file.
Macros | |
#define | GLM_FORCE_RADIANS |
Functions | |
void | GetJStringContent (JNIEnv *AEnv, jstring AStr, std::string &ARes) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_addEnvSensor (JNIEnv *, jclass, jlong native_application, int type, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_cancelProcessing (JNIEnv *env, jclass, jlong native_application) |
JNIEXPORT jlong JNICALL | Java_com_introlab_rtabmap_RTABMapLib_createNativeApplication (JNIEnv *env, jclass, jobject activity) |
JNIEXPORT void | Java_com_introlab_rtabmap_RTABMapLib_destroyNativeApplication (JNIEnv *, jclass, jlong native_application) |
JNIEXPORT bool JNICALL | Java_com_introlab_rtabmap_RTABMapLib_exportMesh (JNIEnv *env, jclass, jlong native_application, float cloudVoxelSize, bool regenerateCloud, bool meshing, int textureSize, int textureCount, int normalK, bool optimized, float optimizedVoxelSize, int optimizedDepth, int optimizedMaxPolygons, float optimizedColorRadius, bool optimizedCleanWhitePolygons, int optimizedMinClusterSize, float optimizedMaxTextureDistance, int optimizedMinTextureClusterSize, bool blockRendering) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_initGlContent (JNIEnv *, jclass, jlong native_application) |
JNIEXPORT bool JNICALL | Java_com_introlab_rtabmap_RTABMapLib_isBuiltWith (JNIEnv *env, jclass, jlong native_application, int cameraDriver) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_onTouchEvent (JNIEnv *, jclass, jlong native_application, int touch_count, int event, float x0, float y0, float x1, float y1) |
JNIEXPORT int JNICALL | Java_com_introlab_rtabmap_RTABMapLib_openDatabase (JNIEnv *env, jclass, jlong native_application, jstring databasePath, bool databaseInMemory, bool optimize, bool clearDatabase) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_postCameraPoseEvent (JNIEnv *env, jclass, jlong native_application, float x, float y, float z, float qx, float qy, float qz, float qw, double stamp) |
JNIEXPORT bool JNICALL | Java_com_introlab_rtabmap_RTABMapLib_postExportation (JNIEnv *env, jclass, jlong native_application, bool visualize) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_postOdometryEvent (JNIEnv *env, jclass, jlong native_application, 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, jobject yPlane, jobject uPlane, jobject vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, jobject 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) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_postOdometryEventDepth (JNIEnv *env, jclass, jlong native_application, 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, jobject yPlane, jobject uPlane, jobject vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, jobject depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, jobject 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) |
JNIEXPORT int JNICALL | Java_com_introlab_rtabmap_RTABMapLib_postProcessing (JNIEnv *env, jclass, jlong native_application, int approach) |
JNIEXPORT bool JNICALL | Java_com_introlab_rtabmap_RTABMapLib_recover (JNIEnv *env, jclass, jlong native_application, jstring from, jstring to) |
JNIEXPORT int JNICALL | Java_com_introlab_rtabmap_RTABMapLib_render (JNIEnv *, jclass, jlong native_application) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_save (JNIEnv *env, jclass, jlong native_application, jstring databasePath) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setAppendMode (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setBackfaceCulling (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setBackgroundColor (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setCamera (JNIEnv *, jclass, jlong native_application, int camera_index) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setCameraColor (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setCloudDensityLevel (JNIEnv *, jclass, jlong native_application, int value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setClusterRatio (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setDataRecorderMode (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setDepthFromMotion (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setFOV (JNIEnv *, jclass, jlong native_application, float fov) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setFullResolution (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setGPS (JNIEnv *, jclass, jlong native_application, double stamp, double longitude, double latitude, double altitude, double accuracy, double bearing) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setGraphOptimization (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setGraphVisible (JNIEnv *, jclass, jlong native_application, bool visible) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setGridRotation (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setGridVisible (JNIEnv *, jclass, jlong native_application, bool visible) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setLighting (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setLocalizationMode (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMapCloudShown (JNIEnv *, jclass, jlong native_application, bool shown) |
JNIEXPORT jint JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMappingParameter (JNIEnv *env, jclass, jlong native_application, jstring key, jstring value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMaxCloudDepth (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMaxGainRadius (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMeshAngleTolerance (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMeshRendering (JNIEnv *, jclass, jlong native_application, bool enabled, bool withTexture) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMeshTriangleSize (JNIEnv *, jclass, jlong native_application, int value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setMinCloudDepth (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setNodesFiltering (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setOdomCloudShown (JNIEnv *, jclass, jlong native_application, bool shown) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setOnlineBlending (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setOrthoCropFactor (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setPausedMapping (JNIEnv *, jclass, jlong native_application, bool paused) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setPointSize (JNIEnv *, jclass, jlong native_application, float value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setRawScanSaved (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setRenderingTextureDecimation (JNIEnv *, jclass, jlong native_application, int value) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setScreenRotation (JNIEnv *env, jclass, jlong native_application, int displayRotation, int cameraRotation) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setSmoothing (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setTrajectoryMode (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setupGraphic (JNIEnv *, jclass, jlong native_application, jint width, jint height) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_setWireframe (JNIEnv *, jclass, jlong native_application, bool enabled) |
JNIEXPORT bool JNICALL | Java_com_introlab_rtabmap_RTABMapLib_startCamera (JNIEnv *env, jclass, jlong native_application, jobject iBinder, jobject context, jobject activity, int driver) |
JNIEXPORT void JNICALL | Java_com_introlab_rtabmap_RTABMapLib_stopCamera (JNIEnv *, jclass, jlong native_application) |
JNIEXPORT bool JNICALL | Java_com_introlab_rtabmap_RTABMapLib_writeExportedMesh (JNIEnv *env, jclass, jlong native_application, jstring directory, jstring name) |
jlong | jptr (RTABMapApp *native_computer_vision_application) |
RTABMapApp * | native (jlong ptr) |
#define GLM_FORCE_RADIANS |
Definition at line 28 of file jni_interface.cpp.
void GetJStringContent | ( | JNIEnv * | AEnv, |
jstring | AStr, | ||
std::string & | ARes | ||
) |
Definition at line 38 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_addEnvSensor | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
int | type, | ||
float | value | ||
) |
Definition at line 727 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_cancelProcessing | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application | ||
) |
Definition at line 759 of file jni_interface.cpp.
JNIEXPORT jlong JNICALL Java_com_introlab_rtabmap_RTABMapLib_createNativeApplication | ( | JNIEnv * | env, |
jclass | , | ||
jobject | activity | ||
) |
Definition at line 58 of file jni_interface.cpp.
JNIEXPORT void Java_com_introlab_rtabmap_RTABMapLib_destroyNativeApplication | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application | ||
) |
Definition at line 64 of file jni_interface.cpp.
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_exportMesh | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
float | cloudVoxelSize, | ||
bool | regenerateCloud, | ||
bool | meshing, | ||
int | textureSize, | ||
int | textureCount, | ||
int | normalK, | ||
bool | optimized, | ||
float | optimizedVoxelSize, | ||
int | optimizedDepth, | ||
int | optimizedMaxPolygons, | ||
float | optimizedColorRadius, | ||
bool | optimizedCleanWhitePolygons, | ||
int | optimizedMinClusterSize, | ||
float | optimizedMaxTextureDistance, | ||
int | optimizedMinTextureClusterSize, | ||
bool | blockRendering | ||
) |
Definition at line 773 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_initGlContent | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application | ||
) |
Definition at line 155 of file jni_interface.cpp.
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_isBuiltWith | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
int | cameraDriver | ||
) |
Definition at line 127 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_onTouchEvent | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
int | touch_count, | ||
int | event, | ||
float | x0, | ||
float | y0, | ||
float | x1, | ||
float | y1 | ||
) |
Definition at line 224 of file jni_interface.cpp.
JNIEXPORT int JNICALL Java_com_introlab_rtabmap_RTABMapLib_openDatabase | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
jstring | databasePath, | ||
bool | databaseInMemory, | ||
bool | optimize, | ||
bool | clearDatabase | ||
) |
Definition at line 91 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_postCameraPoseEvent | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
float | x, | ||
float | y, | ||
float | z, | ||
float | qx, | ||
float | qy, | ||
float | qz, | ||
float | qw, | ||
double | stamp | ||
) |
Definition at line 870 of file jni_interface.cpp.
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_postExportation | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
bool | visualize | ||
) |
Definition at line 820 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_postOdometryEvent | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
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, | ||
jobject | yPlane, | ||
jobject | uPlane, | ||
jobject | vPlane, | ||
int | yPlaneLen, | ||
int | rgbWidth, | ||
int | rgbHeight, | ||
int | rgbFormat, | ||
jobject | 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 | ||
) |
Definition at line 886 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_postOdometryEventDepth | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
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, | ||
jobject | yPlane, | ||
jobject | uPlane, | ||
jobject | vPlane, | ||
int | yPlaneLen, | ||
int | rgbWidth, | ||
int | rgbHeight, | ||
int | rgbFormat, | ||
jobject | depth, | ||
int | depthLen, | ||
int | depthWidth, | ||
int | depthHeight, | ||
int | depthFormat, | ||
jobject | 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 | ||
) |
Definition at line 928 of file jni_interface.cpp.
JNIEXPORT int JNICALL Java_com_introlab_rtabmap_RTABMapLib_postProcessing | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
int | approach | ||
) |
Definition at line 855 of file jni_interface.cpp.
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_recover | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
jstring | from, | ||
jstring | to | ||
) |
Definition at line 108 of file jni_interface.cpp.
JNIEXPORT int JNICALL Java_com_introlab_rtabmap_RTABMapLib_render | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application | ||
) |
Definition at line 181 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_save | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
jstring | databasePath | ||
) |
Definition at line 743 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setAppendMode | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 541 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setBackfaceCulling | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 372 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setBackgroundColor | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 671 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setCamera | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
int | camera_index | ||
) |
Definition at line 208 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setCameraColor | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 528 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setCloudDensityLevel | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
int | value | ||
) |
Definition at line 593 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setClusterRatio | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 632 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setDataRecorderMode | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 554 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setDepthFromMotion | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 515 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setFOV | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | fov | ||
) |
Definition at line 320 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setFullResolution | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 489 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setGPS | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
double | stamp, | ||
double | longitude, | ||
double | latitude, | ||
double | altitude, | ||
double | accuracy, | ||
double | bearing | ||
) |
Definition at line 702 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setGraphOptimization | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 424 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setGraphVisible | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | visible | ||
) |
Definition at line 450 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setGridRotation | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 346 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setGridVisible | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | visible | ||
) |
Definition at line 463 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setLighting | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 359 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setLocalizationMode | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 398 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMapCloudShown | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | shown | ||
) |
Definition at line 267 of file jni_interface.cpp.
JNIEXPORT jint JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMappingParameter | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
jstring | key, | ||
jstring | value | ||
) |
Definition at line 684 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMaxCloudDepth | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 567 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMaxGainRadius | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 645 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMeshAngleTolerance | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 606 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMeshRendering | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled, | ||
bool | withTexture | ||
) |
Definition at line 293 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMeshTriangleSize | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
int | value | ||
) |
Definition at line 619 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMinCloudDepth | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 580 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setNodesFiltering | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 437 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setOdomCloudShown | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | shown | ||
) |
Definition at line 280 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setOnlineBlending | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 254 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setOrthoCropFactor | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 333 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setPausedMapping | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | paused | ||
) |
Definition at line 241 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setPointSize | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
float | value | ||
) |
Definition at line 306 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setRawScanSaved | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 476 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setRenderingTextureDecimation | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
int | value | ||
) |
Definition at line 658 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setScreenRotation | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
int | displayRotation, | ||
int | cameraRotation | ||
) |
Definition at line 77 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setSmoothing | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 502 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setTrajectoryMode | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 411 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setupGraphic | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
jint | width, | ||
jint | height | ||
) |
Definition at line 168 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setWireframe | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application, | ||
bool | enabled | ||
) |
Definition at line 385 of file jni_interface.cpp.
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_startCamera | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
jobject | iBinder, | ||
jobject | context, | ||
jobject | activity, | ||
int | driver | ||
) |
Definition at line 141 of file jni_interface.cpp.
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_stopCamera | ( | JNIEnv * | , |
jclass | , | ||
jlong | native_application | ||
) |
Definition at line 195 of file jni_interface.cpp.
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_writeExportedMesh | ( | JNIEnv * | env, |
jclass | , | ||
jlong | native_application, | ||
jstring | directory, | ||
jstring | name | ||
) |
Definition at line 835 of file jni_interface.cpp.
|
inline |
Definition at line 49 of file jni_interface.cpp.
|
inline |
Definition at line 53 of file jni_interface.cpp.