28 #ifndef RTABMAP_APP_H_ 29 #define RTABMAP_APP_H_ 34 #include <tango_client_api.h> 44 #include <boost/thread/mutex.hpp> 45 #include <pcl/pcl_base.h> 46 #include <pcl/TextureMesh.h> 55 void onCreate(JNIEnv* env, jobject caller_activity);
59 int openDatabase(
const std::string & databasePath,
bool databaseInMemory,
bool optimize,
const std::string & databaseSource=std::string());
114 float x0,
float y0,
float x1,
float y1);
153 void save(
const std::string & databasePath);
156 float cloudVoxelSize,
157 bool regenerateCloud,
163 float optimizedVoxelSize,
165 int optimizedMaxPolygons,
166 float optimizedColorRadius,
167 bool optimizedCleanWhitePolygons,
168 int optimizedMinClusterSize,
169 float optimizedMaxTextureDistance,
170 int optimizedMinTextureClusterSize,
171 bool blockRendering);
183 std::vector<pcl::Vertices>
filterOrganizedPolygons(
const std::vector<pcl::Vertices> & polygons,
int cloudSize)
const;
184 std::vector<pcl::Vertices>
filterPolygons(
const std::vector<pcl::Vertices> & polygons,
int cloudSize)
const;
264 std::pair<rtabmap::RtabmapEventInit::Status, std::string>
status_;
269 #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 onCreate(JNIEnv *env, jobject caller_activity)
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)
int setMappingParameter(const std::string &key, const std::string &value)
void SetViewPort(int width, int height)
double lastPoseEventTime_
void setSmoothing(bool enabled)
int lastDrawnCloudsCount_
std::vector< pcl::Vertices > filterOrganizedPolygons(const std::vector< pcl::Vertices > &polygons, int cloudSize) const
void setGraphOptimization(bool enabled)
std::map< int, Mesh > createdMeshes_
bool onTangoServiceConnected(JNIEnv *env, jobject iBinder)
void setGraphVisible(bool visible)
rtabmap::ParametersMap getRtabmapParameters()
void onPoseAvailable(const TangoPoseData *pose)
boost::mutex visLocalizationMutex_
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)
bool smoothMesh(int id, Mesh &mesh)
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)
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)
void TangoResetMotionTracking()
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_
void setMinCloudDepth(float value)
rtabmap::Transform mapToOdom_
std::pair< rtabmap::RtabmapEventInit::Status, std::string > status_
void setOnlineBlending(bool enabled)
bool exportedMeshUpdated_
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)
float meshAngleToleranceDeg_
std::list< rtabmap::Transform > poseEvents_
USemaphore screenshotReady_
void setFullResolution(bool enabled)
void setMeshAngleTolerance(float value)
std::list< rtabmap::OdometryEvent > odomEvents_
void setScreenRotation(int displayRotation, int cameraRotation)
rtabmap::Rtabmap * rtabmap_
bool bilateralFilteringOnNextRender_
rtabmap::ParametersMap mappingParameters_
rtabmap::ProgressionStatus progressionStatus_
void onTangoEventAvailable(const TangoEvent *event)
void setLighting(bool enabled)
rtabmap::Transform * optRefPose_
rtabmap::CameraTango * camera_
void onPointCloudAvailable(const TangoXYZij *xyz_ij)
void setPausedMapping(bool paused)
void setOdomCloudShown(bool shown)
std::list< rtabmap::RtabmapEvent * > visLocalizationEvents_
void setLocalizationMode(bool enabled)