NativeWrapper.cpp
Go to the documentation of this file.
1 //
2 // PCLWrapper.cpp
3 // ThreeDScanner
4 //
5 // Created by Steven Roach on 2/9/18.
6 // Copyright © 2018 Steven Roach. All rights reserved.
7 //
8 
9 #include "NativeWrapper.hpp"
10 #include "RTABMapApp.h"
12 
13 inline RTABMapApp *native(const void *object) {
14  return (RTABMapApp *)object;
15 }
16 
18 {
19  RTABMapApp *app = new RTABMapApp();
20  return (void *)app;
21 }
22 
23 void setupCallbacksNative(const void *object, void * classPtr,
24  void(*progressCallback)(void*, int, int),
25  void(*initCallback)(void *, int, const char*),
26  void(*statsUpdatedCallback)(void *,
27  int, int, int, int,
28  float,
29  int, int, int, int, int ,int,
30  float,
31  int,
32  float,
33  int,
34  float, float, float, float,
35  int, int,
36  float, float, float, float, float, float))
37 {
38  if(object)
39  {
40  native(object)->setupSwiftCallbacks(classPtr, progressCallback, initCallback, statsUpdatedCallback);
41  }
42  else
43  {
44  UERROR("object is null!");
45  }
46 }
47 
48 void destroyNativeApplication(const void *object)
49 {
50  if(object)
51  {
52  delete native(object);
53  }
54  else
55  {
56  UERROR("object is null!");
57  }
58 }
59 
60 void setScreenRotationNative(const void *object, int displayRotation)
61 {
62  if(object)
63  {
64  return native(object)->setScreenRotation(displayRotation, 0);
65  }
66  else
67  {
68  UERROR("object is null!");
69  }
70 }
71 
72 int openDatabaseNative(const void *object, const char * databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
73 {
74  if(object)
75  {
76  return native(object)->openDatabase(databasePath, databaseInMemory, optimize, clearDatabase);
77  }
78  else
79  {
80  UERROR("object is null!");
81  return -1;
82  }
83 }
84 
85 void saveNative(const void *object, const char * databasePath)
86 {
87  if(object)
88  {
89  return native(object)->save(databasePath);
90  }
91  else
92  {
93  UERROR("object is null!");
94  }
95 }
96 
97 bool recoverNative(const void *object, const char * from, const char * to)
98 {
99  if(object)
100  {
101  return native(object)->recover(from, to);
102  }
103  else
104  {
105  UERROR("object is null!");
106  }
107  return false;
108 }
109 
110 void cancelProcessingNative(const void *object)
111 {
112  if(object)
113  {
114  native(object)->cancelProcessing();
115  }
116  else
117  {
118  UERROR("object is null!");
119  }
120 }
121 
122 int postProcessingNative(const void *object, int approach)
123 {
124  if(object)
125  {
126  return native(object)->postProcessing(approach);
127  }
128  else
129  {
130  UERROR("object is null!");
131  }
132  return -1;
133 }
134 
136  const void *object,
137  float cloudVoxelSize,
138  bool regenerateCloud,
139  bool meshing,
140  int textureSize,
141  int textureCount,
142  int normalK,
143  bool optimized,
144  float optimizedVoxelSize,
145  int optimizedDepth,
146  int optimizedMaxPolygons,
147  float optimizedColorRadius,
148  bool optimizedCleanWhitePolygons,
149  int optimizedMinClusterSize,
150  float optimizedMaxTextureDistance,
151  int optimizedMinTextureClusterSize,
152  bool blockRendering)
153 {
154  if(object)
155  {
156  return native(object)->exportMesh(cloudVoxelSize, regenerateCloud, meshing, textureSize, textureCount, normalK, optimized, optimizedVoxelSize, optimizedDepth, optimizedMaxPolygons, optimizedColorRadius, optimizedCleanWhitePolygons, optimizedMinClusterSize, optimizedMaxTextureDistance, optimizedMinTextureClusterSize, blockRendering);
157  }
158  else
159  {
160  UERROR("object is null!");
161  }
162  return false;
163 }
164 
165 bool postExportationNative(const void *object, bool visualize)
166 {
167  if(object)
168  {
169  return native(object)->postExportation(visualize);
170  }
171  else
172  {
173  UERROR("object is null!");
174  }
175  return false;
176 }
177 
178 bool writeExportedMeshNative(const void *object, const char * directory, const char * name)
179 {
180  if(object)
181  {
182  return native(object)->writeExportedMesh(directory, name);
183  }
184  else
185  {
186  UERROR("object is null!");
187  }
188  return false;
189 }
190 
191 void initGlContentNative(const void *object) {
192  if(object)
193  {
194  native(object)->InitializeGLContent();
195  }
196  else
197  {
198  UERROR("object is null!");
199  }
200 }
201 
202 void setupGraphicNative(const void *object, int width, int height) {
203  if(object)
204  {
205  native(object)->SetViewPort(width, height);
206  }
207  else
208  {
209  UERROR("object is null!");
210  }
211 }
212 
213 void onTouchEventNative(const void *object, int touch_count, int event, float x0, float y0, float x1,
214  float y1) {
215  if(object)
216  {
217  using namespace tango_gl;
218  GestureCamera::TouchEvent touch_event =
219  static_cast<GestureCamera::TouchEvent>(event);
220  native(object)->OnTouchEvent(touch_count, touch_event, x0, y0, x1, y1);
221  }
222  else
223  {
224  UERROR("object is null!");
225  }
226 }
227 
228 void setPausedMappingNative(const void *object, bool paused)
229 {
230  if(object)
231  {
232  return native(object)->setPausedMapping(paused);
233  }
234  else
235  {
236  UERROR("object is null!");
237  }
238 }
239 
240 int renderNative(const void *object) {
241  if(object)
242  {
243  return native(object)->Render();
244  }
245  else
246  {
247  UERROR("object is null!");
248  return -1;
249  }
250 }
251 
252 bool startCameraNative(const void *object) {
253  if(object)
254  {
255  return native(object)->startCamera();
256  }
257  else
258  {
259  UERROR("object is null!");
260  return false;
261  }
262 }
263 
264 void stopCameraNative(const void *object) {
265  if(object)
266  {
267  native(object)->stopCamera();
268  }
269  else
270  {
271  UERROR("object is null!");
272  }
273 }
274 
275 void setCameraNative(const void *object, int type) {
276  if(object)
277  {
279  }
280  else
281  {
282  UERROR("object is null!");
283  }
284 }
285 
286 void postCameraPoseEventNative(const void *object,
287  float x, float y, float z, float qx, float qy, float qz, float qw, double stamp)
288 {
289  if(object)
290  {
291  native(object)->postCameraPoseEvent(x,y,z,qx,qy,qz,qw,stamp);
292  }
293  else
294  {
295  UERROR("object is null!");
296  return;
297  }
298 }
299 
300 void postOdometryEventNative(const void *object,
301  float x, float y, float z, float qx, float qy, float qz, float qw,
302  float fx, float fy, float cx, float cy,
303  double stamp,
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)
311 {
312  if(object)
313  {
314  native(object)->postOdometryEvent(
315  rtabmap::Transform(x,y,z,qx,qy,qz,qw),
316  fx,fy,cx,cy, 0,0,0,0,
318  stamp, 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,
323  rtabmap::Transform(vx, vy, vz, vqx, vqy, vqz, vqw),
324  p00, p11, p02, p12, p22, p32, p23,
325  t0, t1, t2, t3, t4, t5, t6, t7);
326  }
327  else
328  {
329  UERROR("object is null!");
330  return;
331  }
332 }
333 
334 ImageNative getPreviewImageNative(const char * databasePath)
335 {
336  ImageNative imageNative;
337  imageNative.data = 0;
338  imageNative.objectPtr = 0;
340  if(driver.openConnection(databasePath))
341  {
342  cv::Mat image = driver.loadPreviewImage();
343  if(image.empty())
344  {
345  return imageNative;
346  }
347  cv::Mat * imagePtr = new cv::Mat();
348  // We should add alpha channel
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);
354  imageNative.objectPtr = imagePtr;
355  imageNative.data = imagePtr->data;
356  imageNative.width = imagePtr->cols;
357  imageNative.height = imagePtr->rows;
358  imageNative.channels = imagePtr->channels();
359  }
360  return imageNative;
361 }
362 
364 {
365  if(image.objectPtr)
366  {
367  delete (cv::Mat*)image.objectPtr;
368  }
369 }
370 
371 
372 // Parameters
373 void setOnlineBlendingNative(const void *object, bool enabled)
374 {
375  if(object)
376  native(object)->setOnlineBlending(enabled);
377  else
378  UERROR("object is null!");
379 }
380 void setMapCloudShownNative(const void *object, bool shown)
381 {
382  if(object)
383  native(object)->setMapCloudShown(shown);
384  else
385  UERROR("object is null!");
386 }
387 void setOdomCloudShownNative(const void *object, bool shown)
388 {
389  if(object)
390  native(object)->setOdomCloudShown(shown);
391  else
392  UERROR("object is null!");
393 }
394 void setMeshRenderingNative(const void *object, bool enabled, bool withTexture)
395 {
396  if(object)
397  native(object)->setMeshRendering(enabled, withTexture);
398  else
399  UERROR("object is null!");
400 }
401 void setPointSizeNative(const void *object, float value)
402 {
403  if(object)
404  native(object)->setPointSize(value);
405  else
406  UERROR("object is null!");
407 }
408 void setFOVNative(const void *object, float angle)
409 {
410  if(object)
411  native(object)->setFOV(angle);
412  else
413  UERROR("object is null!");
414 }
415 void setOrthoCropFactorNative(const void *object, float value)
416 {
417  if(object)
418  native(object)->setOrthoCropFactor(value);
419  else
420  UERROR("object is null!");
421 }
422 void setGridRotationNative(const void *object, float value)
423 {
424  if(object)
425  native(object)->setGridRotation(value);
426  else
427  UERROR("object is null!");
428 }
429 void setLightingNative(const void *object, bool enabled)
430 {
431  if(object)
432  native(object)->setLighting(enabled);
433  else
434  UERROR("object is null!");
435 }
436 void setBackfaceCullingNative(const void *object, bool enabled)
437 {
438  if(object)
439  native(object)->setBackfaceCulling(enabled);
440  else
441  UERROR("object is null!");
442 }
443 void setWireframeNative(const void *object, bool enabled)
444 {
445  if(object)
446  native(object)->setWireframe(enabled);
447  else
448  UERROR("object is null!");
449 }
450 void setLocalizationModeNative(const void *object, bool enabled)
451 {
452  if(object)
453  native(object)->setLocalizationMode(enabled);
454  else
455  UERROR("object is null!");
456 }
457 void setTrajectoryModeNative(const void *object, bool enabled)
458 {
459  if(object)
460  native(object)->setTrajectoryMode(enabled);
461  else
462  UERROR("object is null!");
463 }
464 void setGraphOptimizationNative(const void *object, bool enabled)
465 {
466  if(object)
467  native(object)->setGraphOptimization(enabled);
468  else
469  UERROR("object is null!");
470 }
471 void setNodesFilteringNative(const void *object, bool enabled)
472 {
473  if(object)
474  native(object)->setNodesFiltering(enabled);
475  else
476  UERROR("object is null!");
477 }
478 void setGraphVisibleNative(const void *object, bool visible)
479 {
480  if(object)
481  native(object)->setGraphVisible(visible);
482  else
483  UERROR("object is null!");
484 }
485 void setGridVisibleNative(const void *object, bool visible)
486 {
487  if(object)
488  native(object)->setGridVisible(visible);
489  else
490  UERROR("object is null!");
491 }
492 void setFullResolutionNative(const void *object, bool enabled)
493 {
494  if(object)
495  native(object)->setFullResolution(enabled);
496  else
497  UERROR("object is null!");
498 }
499 void setSmoothingNative(const void *object, bool enabled)
500 {
501  if(object)
502  native(object)->setSmoothing(enabled);
503  else
504  UERROR("object is null!");
505 }
506 void setAppendModeNative(const void *object, bool enabled)
507 {
508  if(object)
509  native(object)->setAppendMode(enabled);
510  else
511  UERROR("object is null!");
512 }
513 void setMaxCloudDepthNative(const void *object, float value)
514 {
515  if(object)
516  native(object)->setMaxCloudDepth(value);
517  else
518  UERROR("object is null!");
519 }
520 void setMinCloudDepthNative(const void *object, float value)
521 {
522  if(object)
523  native(object)->setMinCloudDepth(value);
524  else
525  UERROR("object is null!");
526 }
527 void setCloudDensityLevelNative(const void *object, int value)
528 {
529  if(object)
531  else
532  UERROR("object is null!");
533 }
534 void setMeshAngleToleranceNative(const void *object, float value)
535 {
536  if(object)
538  else
539  UERROR("object is null!");
540 }
541 void setMeshDecimationFactorNative(const void *object, float value)
542 {
543  if(object)
545  else
546  UERROR("object is null!");
547 }
548 void setMeshTriangleSizeNative(const void *object, int value)
549 {
550  if(object)
551  native(object)->setMeshTriangleSize(value);
552  else
553  UERROR("object is null!");
554 }
555 void setClusterRatioNative(const void *object, float value)
556 {
557  if(object)
558  native(object)->setClusterRatio(value);
559  else
560  UERROR("object is null!");
561 }
562 void setMaxGainRadiusNative(const void *object, float value)
563 {
564  if(object)
565  native(object)->setMaxGainRadius(value);
566  else
567  UERROR("object is null!");
568 }
569 void setRenderingTextureDecimationNative(const void *object, int value)
570 {
571  if(object)
573  else
574  UERROR("object is null!");
575 }
576 void setBackgroundColorNative(const void *object, float gray)
577 {
578  if(object)
579  native(object)->setBackgroundColor(gray);
580  else
581  UERROR("object is null!");
582 }
583 void setDepthConfidenceNative(const void *object, int value)
584 {
585  if(object)
586  native(object)->setDepthConfidence(value);
587  else
588  UERROR("object is null!");
589 }
590 int setMappingParameterNative(const void *object, const char * key, const char * value)
591 {
592  if(object)
593  return native(object)->setMappingParameter(key, value);
594  else
595  UERROR("object is null!");
596  return -1;
597 }
598 
599 void setGPSNative(const void *object, double stamp, double longitude, double latitude, double altitude, double accuracy, double bearing)
600 {
601  rtabmap::GPS gps(stamp, longitude, latitude, altitude, accuracy, bearing);
602  if(object)
603  return native(object)->setGPS(gps);
604  else
605  UERROR("object is null!");
606 }
607 
608 void addEnvSensorNative(const void *object, int type, float value)
609 {
610  if(object)
611  return native(object)->addEnvSensor(type, value);
612  else
613  UERROR("object is null!");
614 }
setNodesFilteringNative
void setNodesFilteringNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:471
RTABMapApp::setMinCloudDepth
void setMinCloudDepth(float value)
Definition: RTABMapApp.cpp:2437
setMeshAngleToleranceNative
void setMeshAngleToleranceNative(const void *object, float value)
Definition: NativeWrapper.cpp:534
RTABMapApp::recover
bool recover(const std::string &from, const std::string &to)
Definition: RTABMapApp.cpp:2609
setClusterRatioNative
void setClusterRatioNative(const void *object, float value)
Definition: NativeWrapper.cpp:555
name
postOdometryEventNative
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)
Definition: NativeWrapper.cpp:300
cy
const double cy
RTABMapApp::setSmoothing
void setSmoothing(bool enabled)
Definition: RTABMapApp.cpp:2393
RTABMapApp::setGridRotation
void setGridRotation(float value)
Definition: RTABMapApp.cpp:2300
x1
x1
ImageNative::height
int height
Definition: NativeWrapper.hpp:121
RTABMapApp::setFullResolution
void setFullResolution(bool enabled)
Definition: RTABMapApp.cpp:2385
RTABMapApp.h
setupGraphicNative
void setupGraphicNative(const void *object, int width, int height)
Definition: NativeWrapper.cpp:202
RTABMapApp::setAppendMode
void setAppendMode(bool enabled)
Definition: RTABMapApp.cpp:2409
RTABMapApp::setGraphOptimization
void setGraphOptimization(bool enabled)
Definition: RTABMapApp.cpp:2331
setBackfaceCullingNative
void setBackfaceCullingNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:436
ImageNative::width
int width
Definition: NativeWrapper.hpp:120
RTABMapApp::setOnlineBlending
void setOnlineBlending(bool enabled)
Definition: RTABMapApp.cpp:2271
RTABMapApp::setScreenRotation
void setScreenRotation(int displayRotation, int cameraRotation)
Definition: RTABMapApp.cpp:343
rtabmap::DBDriver::openConnection
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
RTABMapApp::SetCameraType
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
Definition: RTABMapApp.cpp:2235
setMeshDecimationFactorNative
void setMeshDecimationFactorNative(const void *object, float value)
Definition: NativeWrapper.cpp:541
fx
const double fx
setMappingParameterNative
int setMappingParameterNative(const void *object, const char *key, const char *value)
Definition: NativeWrapper.cpp:590
setMaxCloudDepthNative
void setMaxCloudDepthNative(const void *object, float value)
Definition: NativeWrapper.cpp:513
setMeshTriangleSizeNative
void setMeshTriangleSizeNative(const void *object, int value)
Definition: NativeWrapper.cpp:548
onTouchEventNative
void onTouchEventNative(const void *object, int touch_count, int event, float x0, float y0, float x1, float y1)
Definition: NativeWrapper.cpp:213
RTABMapApp::setLocalizationMode
void setLocalizationMode(bool enabled)
Definition: RTABMapApp.cpp:2317
setOdomCloudShownNative
void setOdomCloudShownNative(const void *object, bool shown)
Definition: NativeWrapper.cpp:387
setOnlineBlendingNative
void setOnlineBlendingNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:373
RTABMapApp::setWireframe
void setWireframe(bool enabled)
Definition: RTABMapApp.cpp:2312
postCameraPoseEventNative
void postCameraPoseEventNative(const void *object, float x, float y, float z, float qx, float qy, float qz, float qw, double stamp)
Definition: NativeWrapper.cpp:286
rtabmap::GPS
Definition: GPS.h:35
type
RTABMapApp::setMeshTriangleSize
void setMeshTriangleSize(int value)
Definition: RTABMapApp.cpp:2457
RTABMapApp::SetViewPort
void SetViewPort(int width, int height)
Definition: RTABMapApp.cpp:1103
setMeshRenderingNative
void setMeshRenderingNative(const void *object, bool enabled, bool withTexture)
Definition: NativeWrapper.cpp:394
saveNative
void saveNative(const void *object, const char *databasePath)
Definition: NativeWrapper.cpp:85
y
Matrix3f y
RTABMapApp::cancelProcessing
void cancelProcessing()
Definition: RTABMapApp.cpp:2629
getPreviewImageNative
ImageNative getPreviewImageNative(const char *databasePath)
Definition: NativeWrapper.cpp:334
RTABMapApp::setMaxCloudDepth
void setMaxCloudDepth(float value)
Definition: RTABMapApp.cpp:2432
RTABMapApp::setGraphVisible
void setGraphVisible(bool visible)
Definition: RTABMapApp.cpp:2358
releasePreviewImageNative
void releasePreviewImageNative(ImageNative image)
Definition: NativeWrapper.cpp:363
RTABMapApp::stopCamera
void stopCamera()
Definition: RTABMapApp.cpp:963
RTABMapApp::postProcessing
int postProcessing(int approach)
Definition: RTABMapApp.cpp:3616
setGraphOptimizationNative
void setGraphOptimizationNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:464
native
RTABMapApp * native(const void *object)
Definition: NativeWrapper.cpp:13
RTABMapApp
Definition: RTABMapApp.h:53
setRenderingTextureDecimationNative
void setRenderingTextureDecimationNative(const void *object, int value)
Definition: NativeWrapper.cpp:569
NativeWrapper.hpp
ImageNative::channels
int channels
Definition: NativeWrapper.hpp:122
setGridVisibleNative
void setGridVisibleNative(const void *object, bool visible)
Definition: NativeWrapper.cpp:485
RTABMapApp::setRenderingTextureDecimation
void setRenderingTextureDecimation(int value)
Definition: RTABMapApp.cpp:2472
destroyNativeApplication
void destroyNativeApplication(const void *object)
Definition: NativeWrapper.cpp:48
RTABMapApp::setPointSize
void setPointSize(float value)
Definition: RTABMapApp.cpp:2288
RTABMapApp::setGridVisible
void setGridVisible(bool visible)
Definition: RTABMapApp.cpp:2364
setDepthConfidenceNative
void setDepthConfidenceNative(const void *object, int value)
Definition: NativeWrapper.cpp:583
writeExportedMeshNative
bool writeExportedMeshNative(const void *object, const char *directory, const char *name)
Definition: NativeWrapper.cpp:178
optimize
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)
RTABMapApp::setCloudDensityLevel
void setCloudDensityLevel(int value)
Definition: RTABMapApp.cpp:2442
setMapCloudShownNative
void setMapCloudShownNative(const void *object, bool shown)
Definition: NativeWrapper.cpp:380
RTABMapApp::OnTouchEvent
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
Definition: RTABMapApp.cpp:2240
tango_gl::GestureCamera::CameraType
CameraType
Definition: gesture_camera.h:28
openDatabaseNative
int openDatabaseNative(const void *object, const char *databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
Definition: NativeWrapper.cpp:72
app
QApplication * app
Definition: tools/DataRecorder/main.cpp:59
setAppendModeNative
void setAppendModeNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:506
vy
StridedVectorType vy(make_vector(y, *n, std::abs(*incy)))
setFOVNative
void setFOVNative(const void *object, float angle)
Definition: NativeWrapper.cpp:408
RTABMapApp::setMeshAngleTolerance
void setMeshAngleTolerance(float value)
Definition: RTABMapApp.cpp:2447
rtabmap::DBDriverSqlite3
Definition: DBDriverSqlite3.h:40
rtabmap::DBDriver::loadPreviewImage
cv::Mat loadPreviewImage() const
Definition: DBDriver.cpp:1183
createNativeApplication
const void * createNativeApplication()
Definition: NativeWrapper.cpp:17
RTABMapApp::setBackfaceCulling
void setBackfaceCulling(bool enabled)
Definition: RTABMapApp.cpp:2308
RTABMapApp::setMaxGainRadius
void setMaxGainRadius(float value)
Definition: RTABMapApp.cpp:2467
x0
x0
ImageNative::objectPtr
const void * objectPtr
Definition: NativeWrapper.hpp:118
RTABMapApp::postOdometryEvent
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)
Definition: RTABMapApp.cpp:3733
DBDriverSqlite3.h
exportMeshNative
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)
Definition: NativeWrapper.cpp:135
tango_gl::GestureCamera::TouchEvent
TouchEvent
Definition: gesture_camera.h:36
RTABMapApp::save
void save(const std::string &databasePath)
Definition: RTABMapApp.cpp:2557
RTABMapApp::setMeshDecimationFactor
void setMeshDecimationFactor(float value)
Definition: RTABMapApp.cpp:2452
recoverNative
bool recoverNative(const void *object, const char *from, const char *to)
Definition: NativeWrapper.cpp:97
object
z
z
x
x
setCloudDensityLevelNative
void setCloudDensityLevelNative(const void *object, int value)
Definition: NativeWrapper.cpp:527
glm::angle
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
setGPSNative
void setGPSNative(const void *object, double stamp, double longitude, double latitude, double altitude, double accuracy, double bearing)
Definition: NativeWrapper.cpp:599
startCameraNative
bool startCameraNative(const void *object)
Definition: NativeWrapper.cpp:252
RTABMapApp::writeExportedMesh
bool writeExportedMesh(const std::string &directory, const std::string &name)
Definition: RTABMapApp.cpp:3506
RTABMapApp::setLighting
void setLighting(bool enabled)
Definition: RTABMapApp.cpp:2304
setSmoothingNative
void setSmoothingNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:499
RTABMapApp::setDepthConfidence
void setDepthConfidence(int value)
Definition: RTABMapApp.cpp:2486
renderNative
int renderNative(const void *object)
Definition: NativeWrapper.cpp:240
RTABMapApp::setBackgroundColor
void setBackgroundColor(float gray)
Definition: RTABMapApp.cpp:2478
key
const gtsam::Symbol key( 'X', 0)
postProcessingNative
int postProcessingNative(const void *object, int approach)
Definition: NativeWrapper.cpp:122
y1
CEPHES_EXTERN_EXPORT double y1(double x)
RTABMapApp::setMappingParameter
int setMappingParameter(const std::string &key, const std::string &value)
Definition: RTABMapApp.cpp:2495
addEnvSensorNative
void addEnvSensorNative(const void *object, int type, float value)
Definition: NativeWrapper.cpp:608
RTABMapApp::setOrthoCropFactor
void setOrthoCropFactor(float value)
Definition: RTABMapApp.cpp:2296
setLightingNative
void setLightingNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:429
qz
RealQZ< MatrixXf > qz(4)
RTABMapApp::setClusterRatio
void setClusterRatio(float value)
Definition: RTABMapApp.cpp:2462
rtabmap::Transform
Definition: Transform.h:41
RTABMapApp::postCameraPoseEvent
void postCameraPoseEvent(float x, float y, float z, float qx, float qy, float qz, float qw, double stamp)
Definition: RTABMapApp.cpp:3715
cancelProcessingNative
void cancelProcessingNative(const void *object)
Definition: NativeWrapper.cpp:110
setPausedMappingNative
void setPausedMappingNative(const void *object, bool paused)
Definition: NativeWrapper.cpp:228
RTABMapApp::setMapCloudShown
void setMapCloudShown(bool shown)
Definition: RTABMapApp.cpp:2275
initGlContentNative
void initGlContentNative(const void *object)
Definition: NativeWrapper.cpp:191
y0
CEPHES_EXTERN_EXPORT double y0(double x)
setOrthoCropFactorNative
void setOrthoCropFactorNative(const void *object, float value)
Definition: NativeWrapper.cpp:415
RTABMapApp::postExportation
bool postExportation(bool visualize)
Definition: RTABMapApp.cpp:3430
RTABMapApp::openDatabase
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
Definition: RTABMapApp.cpp:356
ImageNative::data
void * data
Definition: NativeWrapper.hpp:119
setFullResolutionNative
void setFullResolutionNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:492
setTrajectoryModeNative
void setTrajectoryModeNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:457
RTABMapApp::setFOV
void setFOV(float angle)
Definition: RTABMapApp.cpp:2292
setPointSizeNative
void setPointSizeNative(const void *object, float value)
Definition: NativeWrapper.cpp:401
RTABMapApp::setGPS
void setGPS(const rtabmap::GPS &gps)
Definition: RTABMapApp.cpp:2539
RTABMapApp::setupSwiftCallbacks
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))
Definition: RTABMapApp.cpp:297
setGridRotationNative
void setGridRotationNative(const void *object, float value)
Definition: NativeWrapper.cpp:422
setWireframeNative
void setWireframeNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:443
p22
p22
setScreenRotationNative
void setScreenRotationNative(const void *object, int displayRotation)
Definition: NativeWrapper.cpp:60
RTABMapApp::setPausedMapping
void setPausedMapping(bool paused)
Definition: RTABMapApp.cpp:2246
setGraphVisibleNative
void setGraphVisibleNative(const void *object, bool visible)
Definition: NativeWrapper.cpp:478
tango_gl
Definition: axis.cpp:20
RTABMapApp::Render
int Render()
Definition: RTABMapApp.cpp:1255
RTABMapApp::exportMesh
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)
Definition: RTABMapApp.cpp:2635
cx
const double cx
RTABMapApp::startCamera
bool startCamera()
Definition: RTABMapApp.cpp:877
postExportationNative
bool postExportationNative(const void *object, bool visualize)
Definition: NativeWrapper.cpp:165
stopCameraNative
void stopCameraNative(const void *object)
Definition: NativeWrapper.cpp:264
setCameraNative
void setCameraNative(const void *object, int type)
Definition: NativeWrapper.cpp:275
RTABMapApp::InitializeGLContent
void InitializeGLContent()
Definition: RTABMapApp.cpp:1093
ImageNative
Definition: NativeWrapper.hpp:116
RTABMapApp::setMeshRendering
void setMeshRendering(bool enabled, bool withTexture)
Definition: RTABMapApp.cpp:2284
UERROR
#define UERROR(...)
setLocalizationModeNative
void setLocalizationModeNative(const void *object, bool enabled)
Definition: NativeWrapper.cpp:450
value
value
RTABMapApp::setNodesFiltering
void setNodesFiltering(bool enabled)
Definition: RTABMapApp.cpp:2353
conf
RTABMapApp::setOdomCloudShown
void setOdomCloudShown(bool shown)
Definition: RTABMapApp.cpp:2279
setMinCloudDepthNative
void setMinCloudDepthNative(const void *object, float value)
Definition: NativeWrapper.cpp:520
setupCallbacksNative
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))
Definition: NativeWrapper.cpp:23
RTABMapApp::addEnvSensor
void addEnvSensor(int type, float value)
Definition: RTABMapApp.cpp:2548
fy
const double fy
vx
StridedVectorType vx(make_vector(x, *n, std::abs(*incx)))
setBackgroundColorNative
void setBackgroundColorNative(const void *object, float gray)
Definition: NativeWrapper.cpp:576
setMaxGainRadiusNative
void setMaxGainRadiusNative(const void *object, float value)
Definition: NativeWrapper.cpp:562
RTABMapApp::setTrajectoryMode
void setTrajectoryMode(bool enabled)
Definition: RTABMapApp.cpp:2325


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:13