jni_interface.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #define GLM_FORCE_RADIANS
29 
30 #include <jni.h>
31 #include <RTABMapApp.h>
32 #include <scene.h>
33 
34 #ifdef __cplusplus
35 extern "C" {
36 #endif
37 
38 void GetJStringContent(JNIEnv *AEnv, jstring AStr, std::string &ARes) {
39  if (!AStr) {
40  ARes.clear();
41  return;
42  }
43 
44  const char *s = AEnv->GetStringUTFChars(AStr,NULL);
45  ARes=s;
46  AEnv->ReleaseStringUTFChars(AStr,s);
47 }
48 
49 inline jlong jptr(RTABMapApp *native_computer_vision_application) {
50  return reinterpret_cast<intptr_t>(native_computer_vision_application);
51 }
52 
53 inline RTABMapApp *native(jlong ptr) {
54  return reinterpret_cast<RTABMapApp *>(ptr);
55 }
56 
57 JNIEXPORT jlong JNICALL
59  JNIEnv* env, jclass, jobject activity)
60 {
61  return jptr(new RTABMapApp(env, activity));
62 }
63 
65  JNIEnv *, jclass, jlong native_application) {
66  if(native_application)
67  {
68  delete native(native_application);
69  }
70  else
71  {
72  UERROR("native_application is null!");
73  }
74 }
75 
76 JNIEXPORT void JNICALL
78  JNIEnv* env, jclass, jlong native_application, int displayRotation, int cameraRotation)
79 {
80  if(native_application)
81  {
82  return native(native_application)->setScreenRotation(displayRotation, cameraRotation);
83  }
84  else
85  {
86  UERROR("native_application is null!");
87  }
88 }
89 
90 JNIEXPORT int JNICALL
92  JNIEnv* env, jclass, jlong native_application, jstring databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
93 {
94  std::string databasePathC;
95  GetJStringContent(env,databasePath,databasePathC);
96  if(native_application)
97  {
98  return native(native_application)->openDatabase(databasePathC, databaseInMemory, optimize, clearDatabase);
99  }
100  else
101  {
102  UERROR("native_application is null!");
103  return -1;
104  }
105 }
106 
107 JNIEXPORT bool JNICALL
109  JNIEnv* env, jclass, jlong native_application, jstring from, jstring to)
110 {
111  if(native_application)
112  {
113  std::string toC;
114  GetJStringContent(env,to,toC);
115  std::string fromC;
116  GetJStringContent(env,from,fromC);
117  return native(native_application)->recover(fromC, toC);
118  }
119  else
120  {
121  UERROR("native_application is null!");
122  return -1;
123  }
124 }
125 
126 JNIEXPORT bool JNICALL
128  JNIEnv* env, jclass, jlong native_application, int cameraDriver) {
129  if(native_application)
130  {
131  return native(native_application)->isBuiltWith(cameraDriver);
132  }
133  else
134  {
135  UERROR("native_application is null!");
136  return false;
137  }
138 }
139 
140 JNIEXPORT bool JNICALL
142  JNIEnv* env, jclass, jlong native_application, jobject iBinder, jobject context, jobject activity, int driver) {
143  if(native_application)
144  {
145  return native(native_application)->startCamera(env, iBinder, context, activity, driver);
146  }
147  else
148  {
149  UERROR("native_application is null!");
150  return false;
151  }
152 }
153 
154 JNIEXPORT void JNICALL
156  JNIEnv*, jclass, jlong native_application) {
157  if(native_application)
158  {
159  native(native_application)->InitializeGLContent();
160  }
161  else
162  {
163  UERROR("native_application is null!");
164  }
165 }
166 
167 JNIEXPORT void JNICALL
169  JNIEnv*, jclass, jlong native_application, jint width, jint height) {
170  if(native_application)
171  {
172  native(native_application)->SetViewPort(width, height);
173  }
174  else
175  {
176  UERROR("native_application is null!");
177  }
178 }
179 
180 JNIEXPORT int JNICALL
182  JNIEnv*, jclass, jlong native_application) {
183  if(native_application)
184  {
185  return native(native_application)->Render();
186  }
187  else
188  {
189  UERROR("native_application is null!");
190  return -1;
191  }
192 }
193 
194 JNIEXPORT void JNICALL
196  JNIEnv*, jclass, jlong native_application) {
197  if(native_application)
198  {
199  native(native_application)->stopCamera();
200  }
201  else
202  {
203  UERROR("native_application is null!");
204  }
205 }
206 
207 JNIEXPORT void JNICALL
209  JNIEnv*, jclass, jlong native_application, int camera_index) {
210  if(native_application)
211  {
212  using namespace tango_gl;
213  GestureCamera::CameraType cam_type =
214  static_cast<GestureCamera::CameraType>(camera_index);
215  native(native_application)->SetCameraType(cam_type);
216  }
217  else
218  {
219  UERROR("native_application is null!");
220  }
221 }
222 
223 JNIEXPORT void JNICALL
225  JNIEnv*, jclass, jlong native_application, int touch_count, int event, float x0, float y0, float x1,
226  float y1) {
227  if(native_application)
228  {
229  using namespace tango_gl;
230  GestureCamera::TouchEvent touch_event =
231  static_cast<GestureCamera::TouchEvent>(event);
232  native(native_application)->OnTouchEvent(touch_count, touch_event, x0, y0, x1, y1);
233  }
234  else
235  {
236  UERROR("native_application is null!");
237  }
238 }
239 
240 JNIEXPORT void JNICALL
242  JNIEnv*, jclass, jlong native_application, bool paused)
243 {
244  if(native_application)
245  {
246  return native(native_application)->setPausedMapping(paused);
247  }
248  else
249  {
250  UERROR("native_application is null!");
251  }
252 }
253 JNIEXPORT void JNICALL
255  JNIEnv*, jclass, jlong native_application, bool enabled)
256 {
257  if(native_application)
258  {
259  return native(native_application)->setOnlineBlending(enabled);
260  }
261  else
262  {
263  UERROR("native_application is null!");
264  }
265 }
266 JNIEXPORT void JNICALL
268  JNIEnv*, jclass, jlong native_application, bool shown)
269 {
270  if(native_application)
271  {
272  return native(native_application)->setMapCloudShown(shown);
273  }
274  else
275  {
276  UERROR("native_application is null!");
277  }
278 }
279 JNIEXPORT void JNICALL
281  JNIEnv*, jclass, jlong native_application, bool shown)
282 {
283  if(native_application)
284  {
285  return native(native_application)->setOdomCloudShown(shown);
286  }
287  else
288  {
289  UERROR("native_application is null!");
290  }
291 }
292 JNIEXPORT void JNICALL
294  JNIEnv*, jclass, jlong native_application, bool enabled, bool withTexture)
295 {
296  if(native_application)
297  {
298  return native(native_application)->setMeshRendering(enabled, withTexture);
299  }
300  else
301  {
302  UERROR("native_application is null!");
303  }
304 }
305 JNIEXPORT void JNICALL
307  JNIEnv*, jclass, jlong native_application, float value)
308 {
309  if(native_application)
310  {
311  return native(native_application)->setPointSize(value);
312  }
313  else
314  {
315  UERROR("native_application is null!");
316  }
317 
318 }
319 JNIEXPORT void JNICALL
321  JNIEnv*, jclass, jlong native_application, float fov)
322 {
323  if(native_application)
324  {
325  return native(native_application)->setFOV(fov);
326  }
327  else
328  {
329  UERROR("native_application is null!");
330  }
331 }
332 JNIEXPORT void JNICALL
334  JNIEnv*, jclass, jlong native_application, float value)
335 {
336  if(native_application)
337  {
338  return native(native_application)->setOrthoCropFactor(value);
339  }
340  else
341  {
342  UERROR("native_application is null!");
343  }
344 }
345 JNIEXPORT void JNICALL
347  JNIEnv*, jclass, jlong native_application, float value)
348 {
349  if(native_application)
350  {
351  return native(native_application)->setGridRotation(value);
352  }
353  else
354  {
355  UERROR("native_application is null!");
356  }
357 }
358 JNIEXPORT void JNICALL
360  JNIEnv*, jclass, jlong native_application, bool enabled)
361 {
362  if(native_application)
363  {
364  return native(native_application)->setLighting(enabled);
365  }
366  else
367  {
368  UERROR("native_application is null!");
369  }
370 }
371 JNIEXPORT void JNICALL
373  JNIEnv*, jclass, jlong native_application, bool enabled)
374 {
375  if(native_application)
376  {
377  return native(native_application)->setBackfaceCulling(enabled);
378  }
379  else
380  {
381  UERROR("native_application is null!");
382  }
383 }
384 JNIEXPORT void JNICALL
386  JNIEnv*, jclass, jlong native_application, bool enabled)
387 {
388  if(native_application)
389  {
390  return native(native_application)->setWireframe(enabled);
391  }
392  else
393  {
394  UERROR("native_application is null!");
395  }
396 }
397 JNIEXPORT void JNICALL
399  JNIEnv*, jclass, jlong native_application, bool enabled)
400 {
401  if(native_application)
402  {
403  return native(native_application)->setLocalizationMode(enabled);
404  }
405  else
406  {
407  UERROR("native_application is null!");
408  }
409 }
410 JNIEXPORT void JNICALL
412  JNIEnv*, jclass, jlong native_application, bool enabled)
413 {
414  if(native_application)
415  {
416  return native(native_application)->setTrajectoryMode(enabled);
417  }
418  else
419  {
420  UERROR("native_application is null!");
421  }
422 }
423 JNIEXPORT void JNICALL
425  JNIEnv*, jclass, jlong native_application, bool enabled)
426 {
427  if(native_application)
428  {
429  return native(native_application)->setGraphOptimization(enabled);
430  }
431  else
432  {
433  UERROR("native_application is null!");
434  }
435 }
436 JNIEXPORT void JNICALL
438  JNIEnv*, jclass, jlong native_application, bool enabled)
439 {
440  if(native_application)
441  {
442  return native(native_application)->setNodesFiltering(enabled);
443  }
444  else
445  {
446  UERROR("native_application is null!");
447  }
448 }
449 JNIEXPORT void JNICALL
451  JNIEnv*, jclass, jlong native_application, bool visible)
452 {
453  if(native_application)
454  {
455  return native(native_application)->setGraphVisible(visible);
456  }
457  else
458  {
459  UERROR("native_application is null!");
460  }
461 }
462 JNIEXPORT void JNICALL
464  JNIEnv*, jclass, jlong native_application, bool visible)
465 {
466  if(native_application)
467  {
468  return native(native_application)->setGridVisible(visible);
469  }
470  else
471  {
472  UERROR("native_application is null!");
473  }
474 }
475 JNIEXPORT void JNICALL
477  JNIEnv*, jclass, jlong native_application, bool enabled)
478 {
479  if(native_application)
480  {
481  return native(native_application)->setRawScanSaved(enabled);
482  }
483  else
484  {
485  UERROR("native_application is null!");
486  }
487 }
488 JNIEXPORT void JNICALL
490  JNIEnv*, jclass, jlong native_application, bool enabled)
491 {
492  if(native_application)
493  {
494  return native(native_application)->setFullResolution(enabled);
495  }
496  else
497  {
498  UERROR("native_application is null!");
499  }
500 }
501 JNIEXPORT void JNICALL
503  JNIEnv*, jclass, jlong native_application, bool enabled)
504 {
505  if(native_application)
506  {
507  return native(native_application)->setSmoothing(enabled);
508  }
509  else
510  {
511  UERROR("native_application is null!");
512  }
513 }
514 JNIEXPORT void JNICALL
516  JNIEnv*, jclass, jlong native_application, bool enabled)
517 {
518  if(native_application)
519  {
520  return native(native_application)->setDepthFromMotion(enabled);
521  }
522  else
523  {
524  UERROR("native_application is null!");
525  }
526 }
527 JNIEXPORT void JNICALL
529  JNIEnv*, jclass, jlong native_application, bool enabled)
530 {
531  if(native_application)
532  {
533  return native(native_application)->setCameraColor(enabled);
534  }
535  else
536  {
537  UERROR("native_application is null!");
538  }
539 }
540 JNIEXPORT void JNICALL
542  JNIEnv*, jclass, jlong native_application, bool enabled)
543 {
544  if(native_application)
545  {
546  return native(native_application)->setAppendMode(enabled);
547  }
548  else
549  {
550  UERROR("native_application is null!");
551  }
552 }
553 JNIEXPORT void JNICALL
555  JNIEnv*, jclass, jlong native_application, bool enabled)
556 {
557  if(native_application)
558  {
559  return native(native_application)->setDataRecorderMode(enabled);
560  }
561  else
562  {
563  UERROR("native_application is null!");
564  }
565 }
566 JNIEXPORT void JNICALL
568  JNIEnv*, jclass, jlong native_application, float value)
569 {
570  if(native_application)
571  {
572  return native(native_application)->setMaxCloudDepth(value);
573  }
574  else
575  {
576  UERROR("native_application is null!");
577  }
578 }
579 JNIEXPORT void JNICALL
581  JNIEnv*, jclass, jlong native_application, float value)
582 {
583  if(native_application)
584  {
585  return native(native_application)->setMinCloudDepth(value);
586  }
587  else
588  {
589  UERROR("native_application is null!");
590  }
591 }
592 JNIEXPORT void JNICALL
594  JNIEnv*, jclass, jlong native_application, int value)
595 {
596  if(native_application)
597  {
598  return native(native_application)->setCloudDensityLevel(value);
599  }
600  else
601  {
602  UERROR("native_application is null!");
603  }
604 }
605 JNIEXPORT void JNICALL
607  JNIEnv*, jclass, jlong native_application, float value)
608 {
609  if(native_application)
610  {
611  return native(native_application)->setMeshAngleTolerance(value);
612  }
613  else
614  {
615  UERROR("native_application is null!");
616  }
617 }
618 JNIEXPORT void JNICALL
620  JNIEnv*, jclass, jlong native_application, int value)
621 {
622  if(native_application)
623  {
624  return native(native_application)->setMeshTriangleSize(value);
625  }
626  else
627  {
628  UERROR("native_application is null!");
629  }
630 }
631 JNIEXPORT void JNICALL
633  JNIEnv*, jclass, jlong native_application, float value)
634 {
635  if(native_application)
636  {
637  return native(native_application)->setClusterRatio(value);
638  }
639  else
640  {
641  UERROR("native_application is null!");
642  }
643 }
644 JNIEXPORT void JNICALL
646  JNIEnv*, jclass, jlong native_application, float value)
647 {
648  if(native_application)
649  {
650  return native(native_application)->setMaxGainRadius(value);
651  }
652  else
653  {
654  UERROR("native_application is null!");
655  }
656 }
657 JNIEXPORT void JNICALL
659  JNIEnv*, jclass, jlong native_application, int value)
660 {
661  if(native_application)
662  {
663  return native(native_application)->setRenderingTextureDecimation(value);
664  }
665  else
666  {
667  UERROR("native_application is null!");
668  }
669 }
670 JNIEXPORT void JNICALL
672  JNIEnv*, jclass, jlong native_application, float value)
673 {
674  if(native_application)
675  {
676  return native(native_application)->setBackgroundColor(value);
677  }
678  else
679  {
680  UERROR("native_application is null!");
681  }
682 }
683 JNIEXPORT jint JNICALL
685  JNIEnv* env, jclass, jlong native_application, jstring key, jstring value)
686 {
687  if(native_application)
688  {
689  std::string keyC, valueC;
690  GetJStringContent(env,key,keyC);
691  GetJStringContent(env,value,valueC);
692  return native(native_application)->setMappingParameter(keyC, valueC);
693  }
694  else
695  {
696  UERROR("native_application is null!");
697  return -1;
698  }
699 }
700 
701 JNIEXPORT void JNICALL
703  JNIEnv*, jclass, jlong native_application,
704  double stamp,
705  double longitude,
706  double latitude,
707  double altitude,
708  double accuracy,
709  double bearing)
710 {
711  if(native_application)
712  {
713  return native(native_application)->setGPS(rtabmap::GPS(stamp,
714  longitude,
715  latitude,
716  altitude,
717  accuracy,
718  bearing));
719  }
720  else
721  {
722  UERROR("native_application is null!");
723  }
724 }
725 
726 JNIEXPORT void JNICALL
728  JNIEnv*, jclass, jlong native_application,
729  int type,
730  float value)
731 {
732  if(native_application)
733  {
734  return native(native_application)->addEnvSensor(type, value);
735  }
736  else
737  {
738  UERROR("native_application is null!");
739  }
740 }
741 
742 JNIEXPORT void JNICALL
744  JNIEnv* env, jclass, jlong native_application, jstring databasePath)
745 {
746  if(native_application)
747  {
748  std::string databasePathC;
749  GetJStringContent(env,databasePath,databasePathC);
750  return native(native_application)->save(databasePathC);
751  }
752  else
753  {
754  UERROR("native_application is null!");
755  }
756 }
757 
758 JNIEXPORT void JNICALL
760  JNIEnv* env, jclass, jlong native_application)
761 {
762  if(native_application)
763  {
764  return native(native_application)->cancelProcessing();
765  }
766  else
767  {
768  UERROR("native_application is null!");
769  }
770 }
771 
772 JNIEXPORT bool JNICALL
774  JNIEnv* env, jclass, jlong native_application,
775  float cloudVoxelSize,
776  bool regenerateCloud,
777  bool meshing,
778  int textureSize,
779  int textureCount,
780  int normalK,
781  bool optimized,
782  float optimizedVoxelSize,
783  int optimizedDepth,
784  int optimizedMaxPolygons,
785  float optimizedColorRadius,
786  bool optimizedCleanWhitePolygons,
787  int optimizedMinClusterSize,
788  float optimizedMaxTextureDistance,
789  int optimizedMinTextureClusterSize,
790  bool blockRendering)
791 {
792  if(native_application)
793  {
794  return native(native_application)->exportMesh(
795  cloudVoxelSize,
796  regenerateCloud,
797  meshing,
798  textureSize,
799  textureCount,
800  normalK,
801  optimized,
802  optimizedVoxelSize,
803  optimizedDepth,
804  optimizedMaxPolygons,
805  optimizedColorRadius,
806  optimizedCleanWhitePolygons,
807  optimizedMinClusterSize,
808  optimizedMaxTextureDistance,
809  optimizedMinTextureClusterSize,
810  blockRendering);
811  }
812  else
813  {
814  UERROR("native_application is null!");
815  return false;
816  }
817 }
818 
819 JNIEXPORT bool JNICALL
821  JNIEnv* env, jclass, jlong native_application, bool visualize)
822 {
823  if(native_application)
824  {
825  return native(native_application)->postExportation(visualize);
826  }
827  else
828  {
829  UERROR("native_application is null!");
830  return false;
831  }
832 }
833 
834 JNIEXPORT bool JNICALL
836  JNIEnv* env, jclass, jlong native_application, jstring directory, jstring name)
837 {
838  if(native_application)
839  {
840  std::string directoryC;
841  GetJStringContent(env,directory,directoryC);
842  std::string nameC;
843  GetJStringContent(env,name,nameC);
844  return native(native_application)->writeExportedMesh(directoryC, nameC);
845  }
846  else
847  {
848  UERROR("native_application is null!");
849  return false;
850  }
851 }
852 
853 
854 JNIEXPORT int JNICALL
856  JNIEnv* env, jclass, jlong native_application, int approach)
857 {
858  if(native_application)
859  {
860  return native(native_application)->postProcessing(approach);
861  }
862  else
863  {
864  UERROR("native_application is null!");
865  return -1;
866  }
867 }
868 
869 JNIEXPORT void JNICALL
871  JNIEnv* env, jclass, jlong native_application,
872  float x, float y, float z, float qx, float qy, float qz, float qw, double stamp)
873 {
874  if(native_application)
875  {
876  native(native_application)->postCameraPoseEvent(x,y,z,qx,qy,qz,qw, stamp);
877  }
878  else
879  {
880  UERROR("native_application is null!");
881  return;
882  }
883 }
884 
885 JNIEXPORT void JNICALL
887  JNIEnv* env, jclass, jlong native_application,
888  float x, float y, float z, float qx, float qy, float qz, float qw,
889  float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy,
890  float rgbFrameX, float rgbFrameY, float rgbFrameZ, float rgbFrameQX, float rgbFrameQY, float rgbFrameQZ, float rgbFrameQW,
891  double stamp,
892  jobject yPlane, jobject uPlane, jobject vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat,
893  jobject points, int pointsLen,
894  float vx, float vy, float vz, float vqx, float vqy, float vqz, float vqw, //view matrix
895  float p00, float p11, float p02, float p12, float p22, float p32, float p23, // projection matrix
896  float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7) // tex coord
897 {
898  if(native_application)
899  {
900  void *yPtr = env->GetDirectBufferAddress(yPlane);
901  void *uPtr = env->GetDirectBufferAddress(uPlane);
902  void *vPtr = env->GetDirectBufferAddress(vPlane);
903  float *pointsPtr = (float *)env->GetDirectBufferAddress(points);
904  native(native_application)->postOdometryEvent(
905  rtabmap::Transform(x,y,z,qx,qy,qz,qw),
906  rgb_fx,rgb_fy,rgb_cx,rgb_cy,
907  0,0,0,0,
908  rtabmap::Transform(rgbFrameX, rgbFrameY, rgbFrameZ, rgbFrameQX, rgbFrameQY, rgbFrameQZ, rgbFrameQW),
910  stamp,
911  0,
912  yPtr, uPtr, vPtr, yPlaneLen, rgbWidth, rgbHeight, rgbFormat,
913  0,0,0,0,0, //depth
914  0,0,0,0,0, //conf
915  pointsPtr, pointsLen, 4,
916  rtabmap::Transform(vx, vy, vz, vqx, vqy, vqz, vqw),
917  p00, p11, p02, p12, p22, p32, p23,
918  t0, t1, t2, t3, t4, t5, t6, t7);
919  }
920  else
921  {
922  UERROR("native_application is null!");
923  return;
924  }
925 }
926 
927 JNIEXPORT void JNICALL
929  JNIEnv* env, jclass, jlong native_application,
930  float x, float y, float z, float qx, float qy, float qz, float qw,
931  float rgb_fx, float rgb_fy, float rgb_cx, float rgb_cy,
932  float depth_fx, float depth_fy, float depth_cx, float depth_cy,
933  float rgbFrameX, float rgbFrameY, float rgbFrameZ, float rgbFrameQX, float rgbFrameQY, float rgbFrameQZ, float rgbFrameQW,
934  float depthFrameX, float depthFrameY, float depthFrameZ, float depthFrameQX, float depthFrameQY, float depthFrameQZ, float depthFrameQW,
935  double rgbStamp,
936  double depthStamp,
937  jobject yPlane, jobject uPlane, jobject vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat,
938  jobject depth, int depthLen, int depthWidth, int depthHeight, int depthFormat,
939  jobject points, int pointsLen,
940  float vx, float vy, float vz, float vqx, float vqy, float vqz, float vqw, //view matrix
941  float p00, float p11, float p02, float p12, float p22, float p32, float p23, // projection matrix
942  float t0, float t1, float t2, float t3, float t4, float t5, float t6, float t7) // tex coord)
943  {
944  void *yPtr = env->GetDirectBufferAddress(yPlane);
945  void *uPtr = env->GetDirectBufferAddress(uPlane);
946  void *vPtr = env->GetDirectBufferAddress(vPlane);
947  void *depthPtr = env->GetDirectBufferAddress(depth);
948  float *pointsPtr = (float *)env->GetDirectBufferAddress(points);
949  native(native_application)->postOdometryEvent(
950  rtabmap::Transform(x,y,z,qx,qy,qz,qw),
951  rgb_fx,rgb_fy,rgb_cx,rgb_cy,
952  depth_fx,depth_fy,depth_cx,depth_cy,
953  rtabmap::Transform(rgbFrameX, rgbFrameY, rgbFrameZ, rgbFrameQX, rgbFrameQY, rgbFrameQZ, rgbFrameQW),
954  rtabmap::Transform(depthFrameX, depthFrameY, depthFrameZ, depthFrameQX, depthFrameQY, depthFrameQZ, depthFrameQW),
955  rgbStamp,
956  depthStamp,
957  yPtr, uPtr, vPtr, yPlaneLen, rgbWidth, rgbHeight, rgbFormat,
958  depthPtr, depthLen, depthWidth, depthHeight, depthFormat,
959  0,0,0,0,0, // conf
960  pointsPtr, pointsLen, 4,
961  rtabmap::Transform(vx, vy, vz, vqx, vqy, vqz, vqw),
962  p00, p11, p02, p12, p22, p32, p23,
963  t0, t1, t2, t3, t4, t5, t6, t7);
964  }
965 
966 
967 #ifdef __cplusplus
968 }
969 #endif
void save(const std::string &databasePath)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_initGlContent(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)
#define NULL
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
void setCameraColor(bool enabled)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setBackfaceCulling(JNIEnv *, jclass, jlong native_application, bool enabled)
void setMaxGainRadius(float value)
void setWireframe(bool enabled)
void setAppendMode(bool enabled)
bool isBuiltWith(int cameraDriver) const
Definition: RTABMapApp.cpp:839
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_setGridRotation(JNIEnv *, jclass, jlong native_application, float value)
int setMappingParameter(const std::string &key, const std::string &value)
void SetViewPort(int width, int height)
void setSmoothing(bool enabled)
JNIEXPORT int JNICALL Java_com_introlab_rtabmap_RTABMapLib_postProcessing(JNIEnv *env, jclass, jlong native_application, int approach)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setLighting(JNIEnv *, jclass, jlong native_application, bool enabled)
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_recover(JNIEnv *env, jclass, jlong native_application, jstring from, jstring to)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMinCloudDepth(JNIEnv *, jclass, jlong native_application, float value)
JNIEXPORT jlong JNICALL Java_com_introlab_rtabmap_RTABMapLib_createNativeApplication(JNIEnv *env, jclass, jobject activity)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setPointSize(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_cancelProcessing(JNIEnv *env, jclass, jlong native_application)
void setGraphOptimization(bool enabled)
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_isBuiltWith(JNIEnv *env, jclass, jlong native_application, int cameraDriver)
void setGraphVisible(bool visible)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setOdomCloudShown(JNIEnv *, jclass, jlong native_application, bool shown)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setSmoothing(JNIEnv *, jclass, jlong native_application, bool enabled)
void setDepthFromMotion(bool enabled)
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)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setOnlineBlending(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_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_addEnvSensor(JNIEnv *, jclass, jlong native_application, int type, float value)
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_setRenderingTextureDecimation(JNIEnv *, jclass, jlong native_application, int 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_setGridVisible(JNIEnv *, jclass, jlong native_application, bool visible)
void setCloudDensityLevel(int value)
void InitializeGLContent()
int postProcessing(int approach)
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_writeExportedMesh(JNIEnv *env, jclass, jlong native_application, jstring directory, jstring name)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setCameraColor(JNIEnv *, jclass, jlong native_application, bool enabled)
void setRenderingTextureDecimation(int value)
void setClusterRatio(float value)
void setOrthoCropFactor(float 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_setMapCloudShown(JNIEnv *, jclass, jlong native_application, bool shown)
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
Definition: RTABMapApp.cpp:352
void setGPS(const rtabmap::GPS &gps)
JNIEXPORT int JNICALL Java_com_introlab_rtabmap_RTABMapLib_openDatabase(JNIEnv *env, jclass, jlong native_application, jstring databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
JNIEXPORT bool JNICALL Java_com_introlab_rtabmap_RTABMapLib_postExportation(JNIEnv *env, jclass, jlong native_application, bool visualize)
void setPointSize(float value)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setAppendMode(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 void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setLocalizationMode(JNIEnv *, jclass, jlong native_application, bool enabled)
void setTrajectoryMode(bool enabled)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setCloudDensityLevel(JNIEnv *, jclass, jlong native_application, int value)
void setFOV(float angle)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setFullResolution(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)
void setMaxCloudDepth(float value)
void setGridRotation(float value)
void setBackfaceCulling(bool enabled)
void setRawScanSaved(bool enabled)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setPausedMapping(JNIEnv *, jclass, jlong native_application, bool paused)
bool postExportation(bool visualize)
void setBackgroundColor(float gray)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMeshTriangleSize(JNIEnv *, jclass, jlong native_application, int value)
void setMeshRendering(bool enabled, bool withTexture)
void cancelProcessing()
void setNodesFiltering(bool enabled)
void setMapCloudShown(bool shown)
JNIEXPORT void Java_com_introlab_rtabmap_RTABMapLib_destroyNativeApplication(JNIEnv *, jclass, jlong native_application)
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_onTouchEvent(JNIEnv *, jclass, jlong native_application, int touch_count, int event, float x0, float y0, float x1, float y1)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setGraphVisible(JNIEnv *, jclass, jlong native_application, bool visible)
jlong jptr(RTABMapApp *native_computer_vision_application)
bool recover(const std::string &from, const std::string &to)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setRawScanSaved(JNIEnv *, jclass, jlong native_application, bool enabled)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMeshAngleTolerance(JNIEnv *, jclass, jlong native_application, float value)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setFOV(JNIEnv *, jclass, jlong native_application, float fov)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setTrajectoryMode(JNIEnv *, jclass, jlong native_application, bool enabled)
void setMinCloudDepth(float value)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setScreenRotation(JNIEnv *env, jclass, jlong native_application, int displayRotation, int cameraRotation)
#define UERROR(...)
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 void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setBackgroundColor(JNIEnv *, jclass, jlong native_application, float value)
void setOnlineBlending(bool enabled)
void setDataRecorderMode(bool enabled)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setOrthoCropFactor(JNIEnv *, jclass, jlong native_application, float value)
bool writeExportedMesh(const std::string &directory, const std::string &name)
void stopCamera()
Definition: RTABMapApp.cpp:946
RTABMapApp * native(jlong ptr)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setGraphOptimization(JNIEnv *, jclass, jlong native_application, bool enabled)
void setMeshTriangleSize(int value)
void setGridVisible(bool visible)
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)
bool startCamera()
Definition: RTABMapApp.cpp:873
void postCameraPoseEvent(float x, float y, float z, float qx, float qy, float qz, float qw, double stamp)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_save(JNIEnv *env, jclass, jlong native_application, jstring databasePath)
void setFullResolution(bool enabled)
void setMeshAngleTolerance(float value)
void addEnvSensor(int type, float value)
void setScreenRotation(int displayRotation, int cameraRotation)
Definition: RTABMapApp.cpp:339
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_stopCamera(JNIEnv *, jclass, jlong native_application)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMeshRendering(JNIEnv *, jclass, jlong native_application, bool enabled, bool withTexture)
void setLighting(bool enabled)
void setPausedMapping(bool paused)
JNIEXPORT void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setMaxCloudDepth(JNIEnv *, jclass, jlong native_application, float value)
void setOdomCloudShown(bool shown)
void GetJStringContent(JNIEnv *AEnv, jstring AStr, std::string &ARes)
void setLocalizationMode(bool enabled)
JNIEXPORT int JNICALL Java_com_introlab_rtabmap_RTABMapLib_render(JNIEnv *, jclass, jlong native_application)
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 void JNICALL Java_com_introlab_rtabmap_RTABMapLib_setDataRecorderMode(JNIEnv *, jclass, jlong native_application, bool enabled)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:28