28 #ifndef RTABMAP_APP_H_ 29 #define RTABMAP_APP_H_ 43 #include <boost/thread/mutex.hpp> 44 #include <pcl/pcl_base.h> 45 #include <pcl/TextureMesh.h> 52 RTABMapApp(JNIEnv* env, jobject caller_activity);
57 int openDatabase(
const std::string & databasePath,
bool databaseInMemory,
bool optimize,
const std::string & databaseSource=std::string());
60 bool startCamera(JNIEnv* env, jobject iBinder, jobject context, jobject activity,
int driver);
89 float x0,
float y0,
float x1,
float y1);
129 void save(
const std::string & databasePath);
132 float cloudVoxelSize,
133 bool regenerateCloud,
139 float optimizedVoxelSize,
141 int optimizedMaxPolygons,
142 float optimizedColorRadius,
143 bool optimizedCleanWhitePolygons,
144 int optimizedMinClusterSize,
145 float optimizedMaxTextureDistance,
146 int optimizedMinTextureClusterSize,
147 bool blockRendering);
153 float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw);
156 float x,
float y,
float z,
float qx,
float qy,
float qz,
float qw,
157 float fx,
float fy,
float cx,
float cy,
159 void * yPlane,
void * uPlane,
void * vPlane,
int yPlaneLen,
int rgbWidth,
int rgbHeight,
int rgbFormat,
160 void * depth,
int depthLen,
int depthWidth,
int depthHeight,
int depthFormat,
161 float * points,
int pointsLen);
170 std::vector<pcl::Vertices>
filterOrganizedPolygons(
const std::vector<pcl::Vertices> & polygons,
int cloudSize)
const;
171 std::vector<pcl::Vertices>
filterPolygons(
const std::vector<pcl::Vertices> & polygons,
int cloudSize)
const;
251 std::pair<rtabmap::RtabmapEventInit::Status, std::string>
status_;
256 #endif // TANGO_POINT_CLOUD_POINT_CLOUD_APP_H_
void save(const std::string &databasePath)
void OnTouchEvent(int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
void setCameraColor(bool enabled)
void setMaxGainRadius(float value)
int openDatabase(const std::string &databasePath, bool databaseInMemory, bool optimize, const std::string &databaseSource=std::string())
void setWireframe(bool enabled)
void setAppendMode(bool enabled)
rtabmap::LogHandler * logHandler_
int setMappingParameter(const std::string &key, const std::string &value)
void SetViewPort(int width, int height)
double lastPoseEventTime_
void setSmoothing(bool enabled)
int lastDrawnCloudsCount_
void postCameraPoseEvent(float x, float y, float z, float qx, float qy, float qz, float qw)
std::vector< pcl::Vertices > filterOrganizedPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
void setGraphOptimization(bool enabled)
void setGraphVisible(bool visible)
rtabmap::ParametersMap getRtabmapParameters()
void setDepthFromMotion(bool enabled)
std::map< std::string, std::string > ParametersMap
std::vector< pcl::Vertices > filterPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
GLM_FUNC_DECL T angle(detail::tquat< T, P > const &x)
std::map< std::string, float > bufferedStatsData_
std::list< rtabmap::RtabmapEvent * > rtabmapEvents_
void setCloudDensityLevel(int value)
void InitializeGLContent()
int postProcessing(int approach)
pcl::TextureMesh::Ptr optMesh_
void setRenderingTextureDecimation(int value)
void setClusterRatio(float value)
void setOrthoCropFactor(float value)
void setGPS(const rtabmap::GPS &gps)
void setPointSize(float value)
bool filterPolygonsOnNextRender_
bool takeScreenshotOnNextRender_
boost::mutex rtabmapMutex_
bool clearSceneOnNextRender_
void setTrajectoryMode(bool enabled)
bool startCamera(JNIEnv *env, jobject iBinder, jobject context, jobject activity, int driver)
virtual bool handleEvent(UEvent *event)
std::map< int, rtabmap::Transform > rawPoses_
void setMaxCloudDepth(float value)
void setGridRotation(float value)
int renderingTextureDecimation_
void setBackfaceCulling(bool enabled)
void setRawScanSaved(bool enabled)
void SetCameraType(tango_gl::GestureCamera::CameraType camera_type)
bool isBuiltWith(int cameraDriver) const
void postOdometryEvent(float x, float y, float z, float qx, float qy, float qz, float qw, float fx, float fy, float cx, float cy, double stamp, void *yPlane, void *uPlane, void *vPlane, int yPlaneLen, int rgbWidth, int rgbHeight, int rgbFormat, void *depth, int depthLen, int depthWidth, int depthHeight, int depthFormat, float *points, int pointsLen)
int gainCompensationOnNextRender_
bool postExportation(bool visualize)
void setBackgroundColor(float gray)
void setMeshRendering(bool enabled, bool withTexture)
void setNodesFiltering(bool enabled)
boost::mutex meshesMutex_
double lastPostRenderEventTime_
void setMapCloudShown(bool shown)
rtabmap::RtabmapThread * rtabmapThread_
boost::mutex cameraMutex_
void setMinCloudDepth(float value)
rtabmap::Transform mapToOdom_
std::pair< rtabmap::RtabmapEventInit::Status, std::string > status_
void setOnlineBlending(bool enabled)
bool exportedMeshUpdated_
std::map< int, rtabmap::Mesh > createdMeshes_
void gainCompensation(bool full=false)
void setDataRecorderMode(bool enabled)
bool writeExportedMesh(const std::string &directory, const std::string &name)
bool cameraJustInitialized_
boost::mutex renderingMutex_
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)
RTABMapApp(JNIEnv *env, jobject caller_activity)
float meshAngleToleranceDeg_
std::list< rtabmap::Transform > poseEvents_
bool smoothMesh(int id, rtabmap::Mesh &mesh)
USemaphore screenshotReady_
void setFullResolution(bool enabled)
void setMeshAngleTolerance(float value)
std::list< rtabmap::OdometryEvent > odomEvents_
void addEnvSensor(int type, float value)
void setScreenRotation(int displayRotation, int cameraRotation)
rtabmap::Rtabmap * rtabmap_
bool bilateralFilteringOnNextRender_
rtabmap::ParametersMap mappingParameters_
rtabmap::ProgressionStatus progressionStatus_
void setLighting(bool enabled)
rtabmap::CameraMobile * camera_
rtabmap::Transform * optRefPose_
void setPausedMapping(bool paused)
void setOdomCloudShown(bool shown)
void setLocalizationMode(bool enabled)