Go to the documentation of this file.
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),
37 void(*cameraInfoEventCallback)(
void *,
int,
const char*,
const char*))
41 native(
object)->
setupSwiftCallbacks(classPtr, progressCallback, initCallback, statsUpdatedCallback, cameraInfoEventCallback);
73 int openDatabaseNative(
const void *
object,
const char * databasePath,
bool databaseInMemory,
bool optimize,
bool clearDatabase)
86 void saveNative(
const void *
object,
const char * databasePath)
98 bool recoverNative(
const void *
object,
const char * from,
const char * to)
106 UERROR(
"object is null!");
119 UERROR(
"object is null!");
131 UERROR(
"object is null!");
138 float cloudVoxelSize,
139 bool regenerateCloud,
145 float optimizedVoxelSize,
147 int optimizedMaxPolygons,
148 float optimizedColorRadius,
149 bool optimizedCleanWhitePolygons,
150 int optimizedMinClusterSize,
151 float optimizedMaxTextureDistance,
152 int optimizedMinTextureClusterSize,
153 int textureVertexColorPolicy,
158 return native(
object)->
exportMesh(cloudVoxelSize, regenerateCloud, meshing, textureSize, textureCount, normalK, optimized, optimizedVoxelSize, optimizedDepth, optimizedMaxPolygons, optimizedColorRadius, optimizedCleanWhitePolygons, optimizedMinClusterSize, optimizedMaxTextureDistance, optimizedMinTextureClusterSize, textureVertexColorPolicy, blockRendering);
162 UERROR(
"object is null!");
175 UERROR(
"object is null!");
188 UERROR(
"object is null!");
200 UERROR(
"object is null!");
211 UERROR(
"object is null!");
215 void onTouchEventNative(
const void *
object,
int touch_count,
int event,
float x0,
float y0,
float x1,
226 UERROR(
"object is null!");
238 UERROR(
"object is null!");
249 UERROR(
"object is null!");
261 UERROR(
"object is null!");
273 UERROR(
"object is null!");
284 UERROR(
"object is null!");
289 float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw,
290 float fx,
float fy,
float cx,
float cy,
292 const void * yPlane,
const void * uPlane,
const void * vPlane,
int yPlaneLen,
int rgbWidth,
int rgbHeight,
int rgbFormat,
293 const void * depth,
int depthLen,
int depthWidth,
int depthHeight,
int depthFormat,
294 const void *
conf,
int confLen,
int confWidth,
int confHeight,
int confFormat,
295 const void * points,
int pointsLen,
int pointsChannels,
296 float vx,
float vy,
float vz,
float vqx,
float vqy,
float vqz,
float vqw,
297 float p00,
float p11,
float p02,
float p12,
float p22,
float p32,
float p23,
298 float t0,
float t1,
float t2,
float t3,
float t4,
float t5,
float t6,
float t7)
307 yPlane, uPlane, vPlane, yPlaneLen, rgbWidth, rgbHeight, rgbFormat,
308 depth, depthLen, depthWidth, depthHeight, depthFormat,
309 conf, confLen, confWidth, confHeight, confFormat,
310 (
const float *)points, pointsLen, pointsChannels,
312 p00, p11, p02, p12,
p22, p32, p23,
313 t0, t1, t2, t3, t4, t5, t6, t7);
317 UERROR(
"object is null!");
325 imageNative.
data = 0;
335 cv::Mat * imagePtr =
new cv::Mat();
337 cv::cvtColor(image, *imagePtr, cv::COLOR_BGR2BGRA);
338 std::vector<cv::Mat> channels;
339 cv::split(*imagePtr, channels);
340 channels.back() = cv::Scalar(255);
341 cv::merge(channels, *imagePtr);
343 imageNative.
data = imagePtr->data;
344 imageNative.
width = imagePtr->cols;
345 imageNative.
height = imagePtr->rows;
346 imageNative.
channels = imagePtr->channels();
366 UERROR(
"object is null!");
373 UERROR(
"object is null!");
380 UERROR(
"object is null!");
387 UERROR(
"object is null!");
394 UERROR(
"object is null!");
401 UERROR(
"object is null!");
408 UERROR(
"object is null!");
415 UERROR(
"object is null!");
422 UERROR(
"object is null!");
429 UERROR(
"object is null!");
436 UERROR(
"object is null!");
443 UERROR(
"object is null!");
450 UERROR(
"object is null!");
457 UERROR(
"object is null!");
464 UERROR(
"object is null!");
471 UERROR(
"object is null!");
478 UERROR(
"object is null!");
485 UERROR(
"object is null!");
492 UERROR(
"object is null!");
499 UERROR(
"object is null!");
506 UERROR(
"object is null!");
513 UERROR(
"object is null!");
520 UERROR(
"object is null!");
527 UERROR(
"object is null!");
534 UERROR(
"object is null!");
541 UERROR(
"object is null!");
548 UERROR(
"object is null!");
555 UERROR(
"object is null!");
562 UERROR(
"object is null!");
569 UERROR(
"object is null!");
576 UERROR(
"object is null!");
583 UERROR(
"object is null!");
590 UERROR(
"object is null!");
597 UERROR(
"object is null!");
605 UERROR(
"object is null!");
613 UERROR(
"object is null!");
617 void setGPSNative(
const void *
object,
double stamp,
double longitude,
double latitude,
double altitude,
double accuracy,
double bearing)
619 rtabmap::GPS gps(stamp, longitude, latitude, altitude, accuracy, bearing);
623 UERROR(
"object is null!");
631 UERROR(
"object is null!");
639 UERROR(
"object is null!");
646 UERROR(
"object is null!");
653 UERROR(
"object is null!");
660 UERROR(
"object is null!");
667 UERROR(
"object is null!");
674 UERROR(
"object is null!");
681 UERROR(
"object is null!");
void setNodesFilteringNative(const void *object, bool enabled)
void teleportButtonClicked()
void setMinCloudDepth(float value)
void setMeshAngleToleranceNative(const void *object, float value)
bool recover(const std::string &from, const std::string &to)
void setClusterRatioNative(const void *object, float value)
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)
void setSmoothing(bool enabled)
void setGridRotation(float value)
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
void setFullResolution(bool enabled)
void setDataRecorderModeNative(const void *object, bool enabled)
void setUpstreamRelocalizationAccThrNative(const void *object, float value)
void setupGraphicNative(const void *object, int width, int height)
void setAppendMode(bool enabled)
void setGraphOptimization(bool enabled)
void setBackfaceCullingNative(const void *object, bool enabled)
void teleportNative(const void *object)
void setOnlineBlending(bool enabled)
void setScreenRotation(int displayRotation, int cameraRotation)
bool openConnection(const std::string &url, bool overwritten=false)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
void setMeshDecimationFactorNative(const void *object, float value)
int setMappingParameterNative(const void *object, const char *key, const char *value)
void setMaxCloudDepthNative(const void *object, float value)
void setMeshTriangleSizeNative(const void *object, int value)
void onTouchEventNative(const void *object, int touch_count, int event, float x0, float y0, float x1, float y1)
void setLocalizationMode(bool enabled)
void clearMeasuresNative(const void *object)
void setOdomCloudShownNative(const void *object, bool shown)
void setOnlineBlendingNative(const void *object, bool enabled)
void setWireframe(bool enabled)
void setDataRecorderMode(bool enabled)
void setMeasuringModeNative(const void *object, int mode)
void setMeshTriangleSize(int value)
void SetViewPort(int width, int height)
void setMeshRenderingNative(const void *object, bool enabled, bool withTexture)
void saveNative(const void *object, const char *databasePath)
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(*cameraInfoEventCallback)(void *, int, const char *, const char *))
void setMetricSystem(bool enabled)
ImageNative getPreviewImageNative(const char *databasePath)
void setTextureColorSeamsHidden(bool hidden)
void setMaxCloudDepth(float value)
void setMeasuringTextSize(float size)
void setGraphVisible(bool visible)
void releasePreviewImageNative(ImageNative image)
void removeMeasureNative(const void *object)
int postProcessing(int approach)
void setGraphOptimizationNative(const void *object, bool enabled)
RTABMapApp * native(const void *object)
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, int textureVertexColorPolicy, bool blockRendering)
void setRenderingTextureDecimationNative(const void *object, int value)
void setGridVisibleNative(const void *object, bool visible)
void setRenderingTextureDecimation(int value)
void destroyNativeApplication(const void *object)
void setPointSize(float value)
void setGridVisible(bool visible)
void setDepthConfidenceNative(const void *object, int value)
bool writeExportedMeshNative(const void *object, const char *directory, const char *name)
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)
void setCloudDensityLevel(int value)
void setMapCloudShownNative(const void *object, bool shown)
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
int openDatabaseNative(const void *object, const char *databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
void setAppendModeNative(const void *object, bool enabled)
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
void setFOVNative(const void *object, float angle)
void addMeasureButtonClicked()
void setMeshAngleTolerance(float value)
void setUpstreamRelocalizationAccThr(float value)
cv::Mat loadPreviewImage() const
const void * createNativeApplication()
void setBackfaceCulling(bool enabled)
void setMaxGainRadius(float value)
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, int textureVertexColorPolicy, bool blockRendering)
void save(const std::string &databasePath)
void setMeshDecimationFactor(float value)
bool recoverNative(const void *object, const char *from, const char *to)
void setCloudDensityLevelNative(const void *object, int value)
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
void setGPSNative(const void *object, double stamp, double longitude, double latitude, double altitude, double accuracy, double bearing)
bool startCameraNative(const void *object)
bool writeExportedMesh(const std::string &directory, const std::string &name)
void setLighting(bool enabled)
void setSmoothingNative(const void *object, bool enabled)
void setDepthConfidence(int value)
int renderNative(const void *object)
void setBackgroundColor(float gray)
const gtsam::Symbol key( 'X', 0)
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
int postProcessingNative(const void *object, int approach)
CEPHES_EXTERN_EXPORT double y1(double x)
int setMappingParameter(const std::string &key, const std::string &value)
void addEnvSensorNative(const void *object, int type, float value)
void setOrthoCropFactor(float value)
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(*cameraInfoCallback)(void *, int, const char *, const char *))
void setLightingNative(const void *object, bool enabled)
void setClusterRatio(float value)
void cancelProcessingNative(const void *object)
void setPausedMappingNative(const void *object, bool paused)
void setMapCloudShown(bool shown)
void initGlContentNative(const void *object)
CEPHES_EXTERN_EXPORT double y0(double x)
void setOrthoCropFactorNative(const void *object, float value)
bool postExportation(bool visualize)
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
void setExportPointCloudFormat(const std::string &format)
void setFullResolutionNative(const void *object, bool enabled)
void setTrajectoryModeNative(const void *object, bool enabled)
void setPointSizeNative(const void *object, float value)
void setMeasuringTextSizeNative(const void *object, float size)
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, 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 setGPS(const rtabmap::GPS &gps)
void setGridRotationNative(const void *object, float value)
void setWireframeNative(const void *object, bool enabled)
void setScreenRotationNative(const void *object, int displayRotation)
void setPausedMapping(bool paused)
void setGraphVisibleNative(const void *object, bool visible)
void setExportPointCloudFormatNative(const void *object, const char *format)
void addMeasureNative(const void *object)
bool postExportationNative(const void *object, bool visualize)
void stopCameraNative(const void *object)
void setCameraNative(const void *object, int type)
void InitializeGLContent()
void setMeshRendering(bool enabled, bool withTexture)
void setLocalizationModeNative(const void *object, bool enabled)
void setMetricSystemNative(const void *object, bool enabled)
void setNodesFiltering(bool enabled)
void setOdomCloudShown(bool shown)
void setTextureColorSeamsHiddenNative(const void *object, bool hidden)
void setMinCloudDepthNative(const void *object, float value)
void addEnvSensor(int type, float value)
void setMeasuringMode(int mode)
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
void setBackgroundColorNative(const void *object, float gray)
void setMaxGainRadiusNative(const void *object, float value)
void setTrajectoryMode(bool enabled)
rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:57