24 void(*progressCallback)(
void*,
int,
int),
25 void(*initCallback)(
void *,
int,
const char*),
26 void(*statsUpdatedCallback)(
void *,
29 int,
int,
int,
int,
int ,
int,
34 float,
float,
float,
float,
36 float,
float,
float,
float,
float,
float))
72 int openDatabaseNative(
const void *
object,
const char * databasePath,
bool databaseInMemory,
bool optimize,
bool clearDatabase)
76 return native(
object)->
openDatabase(databasePath, databaseInMemory, optimize, clearDatabase);
85 void saveNative(
const void *
object,
const char * databasePath)
97 bool recoverNative(
const void *
object,
const char * from,
const char * to)
105 UERROR(
"object is null!");
118 UERROR(
"object is null!");
130 UERROR(
"object is null!");
137 float cloudVoxelSize,
138 bool regenerateCloud,
144 float optimizedVoxelSize,
146 int optimizedMaxPolygons,
147 float optimizedColorRadius,
148 bool optimizedCleanWhitePolygons,
149 int optimizedMinClusterSize,
150 float optimizedMaxTextureDistance,
151 int optimizedMinTextureClusterSize,
156 return native(
object)->
exportMesh(cloudVoxelSize, regenerateCloud, meshing, textureSize, textureCount, normalK, optimized, optimizedVoxelSize, optimizedDepth, optimizedMaxPolygons, optimizedColorRadius, optimizedCleanWhitePolygons, optimizedMinClusterSize, optimizedMaxTextureDistance, optimizedMinTextureClusterSize, blockRendering);
160 UERROR(
"object is null!");
173 UERROR(
"object is null!");
186 UERROR(
"object is null!");
198 UERROR(
"object is null!");
209 UERROR(
"object is null!");
213 void onTouchEventNative(
const void *
object,
int touch_count,
int event,
float x0,
float y0,
float x1,
224 UERROR(
"object is null!");
236 UERROR(
"object is null!");
247 UERROR(
"object is null!");
259 UERROR(
"object is null!");
271 UERROR(
"object is null!");
282 UERROR(
"object is null!");
287 float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw)
295 UERROR(
"object is null!");
301 float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw,
302 float fx,
float fy,
float cx,
float cy,
304 const void * yPlane,
const void * uPlane,
const void * vPlane,
int yPlaneLen,
int rgbWidth,
int rgbHeight,
int rgbFormat,
305 const void * depth,
int depthLen,
int depthWidth,
int depthHeight,
int depthFormat,
306 const void * conf,
int confLen,
int confWidth,
int confHeight,
int confFormat,
307 const void * points,
int pointsLen,
int pointsChannels,
308 float vx,
float vy,
float vz,
float vqx,
float vqy,
float vqz,
float vqw,
309 float p00,
float p11,
float p02,
float p12,
float p22,
float p32,
float p23,
310 float t0,
float t1,
float t2,
float t3,
float t4,
float t5,
float t6,
float t7)
316 fx,fy,cx,cy, 0,0,0,0,
319 yPlane, uPlane, vPlane, yPlaneLen, rgbWidth, rgbHeight, rgbFormat,
320 depth, depthLen, depthWidth, depthHeight, depthFormat,
321 conf, confLen, confWidth, confHeight, confFormat,
322 (
const float *)points, pointsLen, pointsChannels,
324 p00, p11, p02, p12, p22, p32, p23,
325 t0, t1, t2, t3, t4, t5, t6, t7);
329 UERROR(
"object is null!");
337 imageNative.
data = 0;
347 cv::Mat * imagePtr =
new cv::Mat();
349 cv::cvtColor(image, *imagePtr, cv::COLOR_BGR2BGRA);
350 std::vector<cv::Mat> channels;
351 cv::split(*imagePtr, channels);
352 channels.back() = cv::Scalar(255);
353 cv::merge(channels, *imagePtr);
355 imageNative.
data = imagePtr->data;
356 imageNative.
width = imagePtr->cols;
357 imageNative.
height = imagePtr->rows;
358 imageNative.
channels = imagePtr->channels();
378 UERROR(
"object is null!");
385 UERROR(
"object is null!");
392 UERROR(
"object is null!");
399 UERROR(
"object is null!");
406 UERROR(
"object is null!");
413 UERROR(
"object is null!");
420 UERROR(
"object is null!");
427 UERROR(
"object is null!");
434 UERROR(
"object is null!");
441 UERROR(
"object is null!");
448 UERROR(
"object is null!");
455 UERROR(
"object is null!");
462 UERROR(
"object is null!");
469 UERROR(
"object is null!");
476 UERROR(
"object is null!");
483 UERROR(
"object is null!");
490 UERROR(
"object is null!");
497 UERROR(
"object is null!");
504 UERROR(
"object is null!");
511 UERROR(
"object is null!");
518 UERROR(
"object is null!");
525 UERROR(
"object is null!");
532 UERROR(
"object is null!");
539 UERROR(
"object is null!");
546 UERROR(
"object is null!");
553 UERROR(
"object is null!");
560 UERROR(
"object is null!");
567 UERROR(
"object is null!");
574 UERROR(
"object is null!");
581 UERROR(
"object is null!");
588 UERROR(
"object is null!");
595 UERROR(
"object is null!");
602 UERROR(
"object is null!");
606 void setGPSNative(
const void *
object,
double stamp,
double longitude,
double latitude,
double altitude,
double accuracy,
double bearing)
608 rtabmap::GPS gps(stamp, longitude, latitude, altitude, accuracy, bearing);
612 UERROR(
"object is null!");
620 UERROR(
"object is null!");
void save(const std::string &databasePath)
bool recoverNative(const void *object, const char *from, const char *to)
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
void setGridVisibleNative(const void *object, bool visible)
void initGlContentNative(const void *object)
int setMappingParameterNative(const void *object, const char *key, const char *value)
void setMeshTriangleSizeNative(const void *object, int value)
void setMaxGainRadius(float value)
void setMapCloudShownNative(const void *object, bool shown)
void setWireframe(bool enabled)
void setAppendMode(bool enabled)
int openDatabaseNative(const void *object, const char *databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
int setMappingParameter(const std::string &key, const std::string &value)
void SetViewPort(int width, int height)
void setSmoothing(bool enabled)
void setMeshRenderingNative(const void *object, bool enabled, bool withTexture)
void setWireframeNative(const void *object, bool enabled)
ImageNative getPreviewImageNative(const char *databasePath)
void setGraphOptimization(bool enabled)
void setGraphOptimizationNative(const void *object, bool enabled)
void setGraphVisible(bool visible)
bool exportMeshNative(const void *object, 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)
void destroyNativeApplication(const void *object)
void setOrthoCropFactorNative(const void *object, float value)
void postOdometryEvent(rtabmap::Transform pose, float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy, float depth_fx, float depth_fy, float depth_cx, float depth_cy, const rtabmap::Transform &rgbFrame, const rtabmap::Transform &depthFrame, double stamp, double depthStamp, const void *yPlane, const void *uPlane, const void *vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, const void *depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, const void *conf, int confLen, int confWidth, int confHeight, int confFormat, const float *points, int pointsLen, int pointsChannels, const rtabmap::Transform &viewMatrix, 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)
void setCloudDensityLevelNative(const void *object, int value)
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
void onTouchEventNative(const void *object, int touch_count, int event, float x0, float y0, float x1, float y1)
void setNodesFilteringNative(const void *object, bool enabled)
void setCloudDensityLevel(int value)
void setAppendModeNative(const void *object, bool enabled)
void setSmoothingNative(const void *object, bool enabled)
void InitializeGLContent()
int postProcessing(int approach)
void setGridRotationNative(const void *object, float value)
void setRenderingTextureDecimation(int value)
void setClusterRatioNative(const void *object, float value)
const void * createNativeApplication()
void setClusterRatio(float value)
void setOrthoCropFactor(float value)
void stopCameraNative(const void *object)
void setCameraNative(const void *object, int type)
bool openConnection(const std::string &url, bool overwritten=false)
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
void setGPS(const rtabmap::GPS &gps)
void setupGraphicNative(const void *object, int width, int height)
void setPointSize(float value)
void setMeshDecimationFactorNative(const void *object, float value)
void setMaxCloudDepthNative(const void *object, float value)
void setMaxGainRadiusNative(const void *object, float value)
void setPointSizeNative(const void *object, float value)
void setRawScanSavedNative(const void *object, bool enabled)
cv::Mat loadPreviewImage() const
void setMeshAngleToleranceNative(const void *object, float value)
void postCameraPoseEventNative(const void *object, float x, float y, float z, float qx, float qy, float qz, float qw)
void setTrajectoryMode(bool enabled)
void setScreenRotationNative(const void *object, int displayRotation)
void postOdometryEventNative(const void *object, float x, float y, float z, float qx, float qy, float qz, float qw, float fx, float fy, float cx, float cy, double stamp, const void *yPlane, const void *uPlane, const void *vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, const void *depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, const void *conf, int confLen, int confWidth, int confHeight, int confFormat, const void *points, int pointsLen, int pointsChannels, 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)
bool postExportationNative(const void *object, bool visualize)
void setMaxCloudDepth(float value)
void cancelProcessingNative(const void *object)
void setGridRotation(float value)
void setBackfaceCulling(bool enabled)
void setRawScanSaved(bool enabled)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
RTABMapApp * native(const void *object)
void setLocalizationModeNative(const void *object, bool enabled)
void setupSwiftCallbacks(void *classPtr, void(*progressCallback)(void *, int, int), void(*initCallback)(void *, int, const char *), void(*statsUpdatedCallback)(void *, int, int, int, int, float, int, int, int, int, int, int, float, int, float, int, float, float, float, float, int, int, float, float, float, float, float, float))
void setMinCloudDepthNative(const void *object, float value)
bool postExportation(bool visualize)
void setBackgroundColor(float gray)
void setTrajectoryModeNative(const void *object, bool enabled)
void setMeshRendering(bool enabled, bool withTexture)
void setNodesFiltering(bool enabled)
void setMapCloudShown(bool shown)
bool recover(const std::string &from, const std::string &to)
void setGPSNative(const void *object, double stamp, double longitude, double latitude, double altitude, double accuracy, double bearing)
bool startCameraNative(const void *object)
void setMeshDecimationFactor(float value)
void saveNative(const void *object, const char *databasePath)
void setGraphVisibleNative(const void *object, bool visible)
int renderNative(const void *object)
void setFOVNative(const void *object, float angle)
void setMinCloudDepth(float value)
void addEnvSensorNative(const void *object, int type, float value)
void setBackfaceCullingNative(const void *object, bool enabled)
void setOnlineBlending(bool enabled)
void setRenderingTextureDecimationNative(const void *object, int value)
bool writeExportedMesh(const std::string &directory, const std::string &name)
void setDepthConfidenceNative(const void *object, int value)
void setupCallbacksNative(const void *object, void *classPtr, void(*progressCallback)(void *, int, int), void(*initCallback)(void *, int, const char *), void(*statsUpdatedCallback)(void *, int, int, int, int, float, int, int, int, int, int, int, float, int, float, int, float, float, float, float, int, int, float, float, float, float, float, float))
void setDepthConfidence(int value)
bool writeExportedMeshNative(const void *object, const char *directory, const char *name)
void setMeshTriangleSize(int value)
void setOdomCloudShownNative(const void *object, bool shown)
void setGridVisible(bool visible)
void setBackgroundColorNative(const void *object, float gray)
bool exportMesh(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)
void setFullResolutionNative(const void *object, bool enabled)
void setOnlineBlendingNative(const void *object, bool enabled)
void postCameraPoseEvent(float x, float y, float z, float qx, float qy, float qz, float qw, double stamp)
void setFullResolution(bool enabled)
void setMeshAngleTolerance(float value)
void addEnvSensor(int type, float value)
void setScreenRotation(int displayRotation, int cameraRotation)
void setLighting(bool enabled)
int postProcessingNative(const void *object, int approach)
void releasePreviewImageNative(ImageNative image)
void setPausedMapping(bool paused)
void setLightingNative(const void *object, bool enabled)
void setOdomCloudShown(bool shown)
void setLocalizationMode(bool enabled)
void setPausedMappingNative(const void *object, bool paused)