Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes | List of all members
RTABMapApp Class Reference

#include <RTABMapApp.h>

Inheritance diagram for RTABMapApp:
Inheritance graph
[legend]

Public Member Functions

void addEnvSensor (int type, float value)
 
void addMeasureButtonClicked ()
 
void cancelProcessing ()
 
void clearMeasures ()
 
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 InitializeGLContent ()
 
bool isBuiltWith (int cameraDriver) const
 
void OnTouchEvent (int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
 
int openDatabase (const std::string &databasePath, bool databaseInMemory, bool optimize, bool clearDatabase)
 
bool postExportation (bool visualize)
 
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)
 
int postProcessing (int approach)
 
bool recover (const std::string &from, const std::string &to)
 
void removeMeasure ()
 
int Render ()
 
 RTABMapApp ()
 
void save (const std::string &databasePath)
 
void setAppendMode (bool enabled)
 
void setBackfaceCulling (bool enabled)
 
void setBackgroundColor (float gray)
 
void setCameraColor (bool enabled)
 
void SetCameraType (tango_gl::GestureCamera::CameraType camera_type)
 
void setCloudDensityLevel (int value)
 
void setClusterRatio (float value)
 
void setDataRecorderMode (bool enabled)
 
void setDepthConfidence (int value)
 
void setDepthFromMotion (bool enabled)
 
void setExportPointCloudFormat (const std::string &format)
 
void setFOV (float angle)
 
void setFullResolution (bool enabled)
 
void setGPS (const rtabmap::GPS &gps)
 
void setGraphOptimization (bool enabled)
 
void setGraphVisible (bool visible)
 
void setGridRotation (float value)
 
void setGridVisible (bool visible)
 
void setLighting (bool enabled)
 
void setLocalizationMode (bool enabled)
 
void setMapCloudShown (bool shown)
 
int setMappingParameter (const std::string &key, const std::string &value)
 
void setMaxCloudDepth (float value)
 
void setMaxGainRadius (float value)
 
void setMeasuringMode (int mode)
 
void setMeasuringTextSize (float size)
 
void setMeshAngleTolerance (float value)
 
void setMeshDecimationFactor (float value)
 
void setMeshRendering (bool enabled, bool withTexture)
 
void setMeshTriangleSize (int value)
 
void setMetricSystem (bool enabled)
 
void setMinCloudDepth (float value)
 
void setNodesFiltering (bool enabled)
 
void setOdomCloudShown (bool shown)
 
void setOnlineBlending (bool enabled)
 
void setOrthoCropFactor (float value)
 
void setPausedMapping (bool paused)
 
void setPointSize (float value)
 
void setRawScanSaved (bool enabled)
 
void setRenderingTextureDecimation (int value)
 
void setScreenRotation (int displayRotation, int cameraRotation)
 
void setSmoothing (bool enabled)
 
void setTextureColorSeamsHidden (bool hidden)
 
void setTrajectoryMode (bool enabled)
 
void setUpstreamRelocalizationAccThr (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 SetViewPort (int width, int height)
 
void setWireframe (bool enabled)
 
void showMeasures (bool x, bool y, bool z, bool custom)
 
bool startCamera ()
 
void stopCamera ()
 
void teleportButtonClicked ()
 
bool writeExportedMesh (const std::string &directory, const std::string &name)
 
 ~RTABMapApp ()
 
- Public Member Functions inherited from UEventsHandler
void registerToEventsManager ()
 
void unregisterFromEventsManager ()
 
- Public Member Functions inherited from UEventsSender
 UEventsSender ()
 
virtual ~UEventsSender ()
 

Protected Member Functions

virtual bool handleEvent (UEvent *event)
 
- Protected Member Functions inherited from UEventsHandler
 UEventsHandler ()
 
virtual ~UEventsHandler ()
 
- Protected Member Functions inherited from UEventsSender
void post (UEvent *event, bool async=true) const
 

Private Member Functions

std::vector< pcl::Vertices > filterOrganizedPolygons (const std::vector< pcl::Vertices > &polygons, int cloudSize) const
 
std::vector< pcl::Vertices > filterPolygons (const std::vector< pcl::Vertices > &polygons, int cloudSize) const
 
void gainCompensation (bool full=false)
 
rtabmap::ParametersMap getRtabmapParameters ()
 
bool smoothMesh (int id, rtabmap::Mesh &mesh)
 
void updateMeasuringState ()
 
int updateMeshDecimation (int width, int height)
 

Private Attributes

bool addMeasureClicked_
 
bool appendMode_
 
float backgroundColor_
 
bool bilateralFilteringOnNextRender_
 
std::map< std::string, floatbufferedStatsData_
 
rtabmap::CameraMobilecamera_
 
bool cameraColor_
 
int cameraDriver_
 
bool cameraJustInitialized_
 
boost::mutex cameraMutex_
 
bool clearSceneOnNextRender_
 
int cloudDensityLevel_
 
float clusterRatio_
 
std::map< int, rtabmap::MeshcreatedMeshes_
 
bool dataRecorderMode_
 
int depthConfidence_
 
bool depthFromMotion_
 
bool exportedMeshUpdated_
 
bool exporting_
 
std::string exportPointCloudFormat_
 
bool filterPolygonsOnNextRender_
 
UTimer fpsTime_
 
bool fullResolution_
 
int gainCompensationOnNextRender_
 
bool graphOptimization_
 
int lastDrawnCloudsCount_
 
double lastPoseEventTime_
 
double lastPostRenderEventTime_
 
bool localizationMode_
 
rtabmap::LogHandlerlogHandler_
 
Scene main_scene_
 
rtabmap::ParametersMap mappingParameters_
 
rtabmap::Transform mapToOdom_
 
float maxCloudDepth_
 
float maxGainRadius_
 
std::list< Measuremeasures_
 
bool measuresUpdated_
 
int measuringMode_
 
float measuringTextSize_
 
std::vector< cv::Point3f > measuringTmpNormals_
 
std::vector< cv::Point3f > measuringTmpPts_
 
float meshAngleToleranceDeg_
 
float meshDecimationFactor_
 
boost::mutex meshesMutex_
 
int meshTrianglePix_
 
bool metricSystem_
 
float minCloudDepth_
 
bool nodesFiltering_
 
bool odomCloudShown_
 
bool openingDatabase_
 
rtabmap::Mesh optMesh_
 
int optRefId_
 
rtabmap::TransformoptRefPose_
 
cv::Mat optTexture_
 
pcl::TextureMesh::Ptr optTextureMesh_
 
std::list< rtabmap::TransformposeEvents_
 
boost::mutex poseMutex_
 
bool postProcessing_
 
rtabmap::ProgressionStatus progressionStatus_
 
pcl::PointCloud< pcl::PointXYZ >::Ptr quadSample_
 
std::vector< pcl::Vertices > quadSamplePolygons_
 
std::map< int, rtabmap::TransformrawPoses_
 
bool rawScanSaved_
 
bool removeMeasureClicked_
 
boost::mutex renderingMutex_
 
int renderingTextureDecimation_
 
float renderingTime_
 
rtabmap::Rtabmaprtabmap_
 
std::list< rtabmap::RtabmapEvent * > rtabmapEvents_
 
boost::mutex rtabmapMutex_
 
rtabmap::RtabmapThreadrtabmapThread_
 
USemaphore screenshotReady_
 
rtabmap::SensorCaptureThreadsensorCaptureThread_
 
std::list< rtabmap::SensorEventsensorEvents_
 
boost::mutex sensorMutex_
 
bool smoothing_
 
std::vector< cv::Vec3f > snapAxes_
 
float snapAxisThr_
 
std::pair< rtabmap::RtabmapEventInit::Status, std::stringstatus_
 
void(* swiftCameraInfoEventCallback )(void *, int, const char *, const char *)
 
void * swiftClassPtr_
 
void(* swiftInitCallback )(void *, int, const char *)
 
void(* swiftStatsUpdatedCallback )(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)
 
bool takeScreenshotOnNextRender_
 
pcl::PointCloud< pcl::PointXYZRGB >::Ptr targetPoint_
 
bool teleportClicked_
 
int totalPoints_
 
int totalPolygons_
 
bool trajectoryMode_
 
float upstreamRelocalizationMaxAcc_
 
bool useExternalLidar_
 
bool visualizingMesh_
 

Detailed Description

Definition at line 54 of file RTABMapApp.h.

Constructor & Destructor Documentation

◆ RTABMapApp()

RTABMapApp::RTABMapApp ( )

Definition at line 218 of file RTABMapApp.cpp.

◆ ~RTABMapApp()

RTABMapApp::~RTABMapApp ( )

Definition at line 355 of file RTABMapApp.cpp.

Member Function Documentation

◆ addEnvSensor()

void RTABMapApp::addEnvSensor ( int  type,
float  value 
)

Definition at line 3186 of file RTABMapApp.cpp.

◆ addMeasureButtonClicked()

void RTABMapApp::addMeasureButtonClicked ( )

Definition at line 4420 of file RTABMapApp.cpp.

◆ cancelProcessing()

void RTABMapApp::cancelProcessing ( )

Definition at line 3270 of file RTABMapApp.cpp.

◆ clearMeasures()

void RTABMapApp::clearMeasures ( )

Definition at line 4405 of file RTABMapApp.cpp.

◆ exportMesh()

bool RTABMapApp::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 
)

Definition at line 3276 of file RTABMapApp.cpp.

◆ filterOrganizedPolygons()

std::vector< pcl::Vertices > RTABMapApp::filterOrganizedPolygons ( const std::vector< pcl::Vertices > &  polygons,
int  cloudSize 
) const
private

Definition at line 1044 of file RTABMapApp.cpp.

◆ filterPolygons()

std::vector< pcl::Vertices > RTABMapApp::filterPolygons ( const std::vector< pcl::Vertices > &  polygons,
int  cloudSize 
) const
private

Definition at line 1111 of file RTABMapApp.cpp.

◆ gainCompensation()

void RTABMapApp::gainCompensation ( bool  full = false)
private

Definition at line 1260 of file RTABMapApp.cpp.

◆ getRtabmapParameters()

rtabmap::ParametersMap RTABMapApp::getRtabmapParameters ( )
private

Definition at line 129 of file RTABMapApp.cpp.

◆ handleEvent()

bool RTABMapApp::handleEvent ( UEvent event)
protectedvirtual

Method called by the UEventsManager to handle an event. Important : this method must do a minimum of work because the faster the dispatching loop is done; the faster the events are received. If a handling function takes too much time, the events list can grow faster than it is emptied. The event can be modified.

Returns
"true" to notify UEventsManager that this handler took ownership of the event (meaning it must delete it). The event will not be dispatched to next handlers.
"false" to let event be dispatched to next handlers (default behavior). UEventsManager will take care of deleting the event.

Implements UEventsHandler.

Definition at line 4705 of file RTABMapApp.cpp.

◆ InitializeGLContent()

void RTABMapApp::InitializeGLContent ( )

Definition at line 1154 of file RTABMapApp.cpp.

◆ isBuiltWith()

bool RTABMapApp::isBuiltWith ( int  cameraDriver) const

Definition at line 896 of file RTABMapApp.cpp.

◆ OnTouchEvent()

void RTABMapApp::OnTouchEvent ( int  touch_count,
tango_gl::GestureCamera::TouchEvent  event,
float  x0,
float  y0,
float  x1,
float  y1 
)

Definition at line 2844 of file RTABMapApp.cpp.

◆ openDatabase()

int RTABMapApp::openDatabase ( const std::string databasePath,
bool  databaseInMemory,
bool  optimize,
bool  clearDatabase 
)

Definition at line 392 of file RTABMapApp.cpp.

◆ postExportation()

bool RTABMapApp::postExportation ( bool  visualize)

Definition at line 4093 of file RTABMapApp.cpp.

◆ postOdometryEvent()

void RTABMapApp::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 
)

Definition at line 4465 of file RTABMapApp.cpp.

◆ postProcessing()

int RTABMapApp::postProcessing ( int  approach)

Definition at line 4306 of file RTABMapApp.cpp.

◆ recover()

bool RTABMapApp::recover ( const std::string from,
const std::string to 
)

Definition at line 3250 of file RTABMapApp.cpp.

◆ removeMeasure()

void RTABMapApp::removeMeasure ( )

Definition at line 4438 of file RTABMapApp.cpp.

◆ Render()

int RTABMapApp::Render ( )

Definition at line 1316 of file RTABMapApp.cpp.

◆ save()

void RTABMapApp::save ( const std::string databasePath)

Definition at line 3195 of file RTABMapApp.cpp.

◆ setAppendMode()

void RTABMapApp::setAppendMode ( bool  enabled)

Definition at line 3026 of file RTABMapApp.cpp.

◆ setBackfaceCulling()

void RTABMapApp::setBackfaceCulling ( bool  enabled)

Definition at line 2921 of file RTABMapApp.cpp.

◆ setBackgroundColor()

void RTABMapApp::setBackgroundColor ( float  gray)

Definition at line 3100 of file RTABMapApp.cpp.

◆ setCameraColor()

void RTABMapApp::setCameraColor ( bool  enabled)

Definition at line 2994 of file RTABMapApp.cpp.

◆ SetCameraType()

void RTABMapApp::SetCameraType ( tango_gl::GestureCamera::CameraType  camera_type)

Definition at line 2839 of file RTABMapApp.cpp.

◆ setCloudDensityLevel()

void RTABMapApp::setCloudDensityLevel ( int  value)

Definition at line 3064 of file RTABMapApp.cpp.

◆ setClusterRatio()

void RTABMapApp::setClusterRatio ( float  value)

Definition at line 3084 of file RTABMapApp.cpp.

◆ setDataRecorderMode()

void RTABMapApp::setDataRecorderMode ( bool  enabled)

Definition at line 3042 of file RTABMapApp.cpp.

◆ setDepthConfidence()

void RTABMapApp::setDepthConfidence ( int  value)

Definition at line 3108 of file RTABMapApp.cpp.

◆ setDepthFromMotion()

void RTABMapApp::setDepthFromMotion ( bool  enabled)

Definition at line 3018 of file RTABMapApp.cpp.

◆ setExportPointCloudFormat()

void RTABMapApp::setExportPointCloudFormat ( const std::string format)

Definition at line 3117 of file RTABMapApp.cpp.

◆ setFOV()

void RTABMapApp::setFOV ( float  angle)

Definition at line 2896 of file RTABMapApp.cpp.

◆ setFullResolution()

void RTABMapApp::setFullResolution ( bool  enabled)

Definition at line 3002 of file RTABMapApp.cpp.

◆ setGPS()

void RTABMapApp::setGPS ( const rtabmap::GPS gps)

Definition at line 3177 of file RTABMapApp.cpp.

◆ setGraphOptimization()

void RTABMapApp::setGraphOptimization ( bool  enabled)

Definition at line 2948 of file RTABMapApp.cpp.

◆ setGraphVisible()

void RTABMapApp::setGraphVisible ( bool  visible)

Definition at line 2975 of file RTABMapApp.cpp.

◆ setGridRotation()

void RTABMapApp::setGridRotation ( float  value)

Definition at line 2904 of file RTABMapApp.cpp.

◆ setGridVisible()

void RTABMapApp::setGridVisible ( bool  visible)

Definition at line 2981 of file RTABMapApp.cpp.

◆ setLighting()

void RTABMapApp::setLighting ( bool  enabled)

Definition at line 2917 of file RTABMapApp.cpp.

◆ setLocalizationMode()

void RTABMapApp::setLocalizationMode ( bool  enabled)

Definition at line 2934 of file RTABMapApp.cpp.

◆ setMapCloudShown()

void RTABMapApp::setMapCloudShown ( bool  shown)

Definition at line 2879 of file RTABMapApp.cpp.

◆ setMappingParameter()

int RTABMapApp::setMappingParameter ( const std::string key,
const std::string value 
)

Definition at line 3133 of file RTABMapApp.cpp.

◆ setMaxCloudDepth()

void RTABMapApp::setMaxCloudDepth ( float  value)

Definition at line 3054 of file RTABMapApp.cpp.

◆ setMaxGainRadius()

void RTABMapApp::setMaxGainRadius ( float  value)

Definition at line 3089 of file RTABMapApp.cpp.

◆ setMeasuringMode()

void RTABMapApp::setMeasuringMode ( int  mode)

Definition at line 4412 of file RTABMapApp.cpp.

◆ setMeasuringTextSize()

void RTABMapApp::setMeasuringTextSize ( float  size)

Definition at line 4456 of file RTABMapApp.cpp.

◆ setMeshAngleTolerance()

void RTABMapApp::setMeshAngleTolerance ( float  value)

Definition at line 3069 of file RTABMapApp.cpp.

◆ setMeshDecimationFactor()

void RTABMapApp::setMeshDecimationFactor ( float  value)

Definition at line 3074 of file RTABMapApp.cpp.

◆ setMeshRendering()

void RTABMapApp::setMeshRendering ( bool  enabled,
bool  withTexture 
)

Definition at line 2888 of file RTABMapApp.cpp.

◆ setMeshTriangleSize()

void RTABMapApp::setMeshTriangleSize ( int  value)

Definition at line 3079 of file RTABMapApp.cpp.

◆ setMetricSystem()

void RTABMapApp::setMetricSystem ( bool  enabled)

Definition at line 4447 of file RTABMapApp.cpp.

◆ setMinCloudDepth()

void RTABMapApp::setMinCloudDepth ( float  value)

Definition at line 3059 of file RTABMapApp.cpp.

◆ setNodesFiltering()

void RTABMapApp::setNodesFiltering ( bool  enabled)

Definition at line 2970 of file RTABMapApp.cpp.

◆ setOdomCloudShown()

void RTABMapApp::setOdomCloudShown ( bool  shown)

Definition at line 2883 of file RTABMapApp.cpp.

◆ setOnlineBlending()

void RTABMapApp::setOnlineBlending ( bool  enabled)

Definition at line 2875 of file RTABMapApp.cpp.

◆ setOrthoCropFactor()

void RTABMapApp::setOrthoCropFactor ( float  value)

Definition at line 2900 of file RTABMapApp.cpp.

◆ setPausedMapping()

void RTABMapApp::setPausedMapping ( bool  paused)

Definition at line 2850 of file RTABMapApp.cpp.

◆ setPointSize()

void RTABMapApp::setPointSize ( float  value)

Definition at line 2892 of file RTABMapApp.cpp.

◆ setRawScanSaved()

void RTABMapApp::setRawScanSaved ( bool  enabled)

Definition at line 2986 of file RTABMapApp.cpp.

◆ setRenderingTextureDecimation()

void RTABMapApp::setRenderingTextureDecimation ( int  value)

Definition at line 3094 of file RTABMapApp.cpp.

◆ setScreenRotation()

void RTABMapApp::setScreenRotation ( int  displayRotation,
int  cameraRotation 
)

Definition at line 379 of file RTABMapApp.cpp.

◆ setSmoothing()

void RTABMapApp::setSmoothing ( bool  enabled)

Definition at line 3010 of file RTABMapApp.cpp.

◆ setTextureColorSeamsHidden()

void RTABMapApp::setTextureColorSeamsHidden ( bool  hidden)

Definition at line 2929 of file RTABMapApp.cpp.

◆ setTrajectoryMode()

void RTABMapApp::setTrajectoryMode ( bool  enabled)

Definition at line 2942 of file RTABMapApp.cpp.

◆ setUpstreamRelocalizationAccThr()

void RTABMapApp::setUpstreamRelocalizationAccThr ( float  value)

Definition at line 3037 of file RTABMapApp.cpp.

◆ setupSwiftCallbacks()

void RTABMapApp::setupSwiftCallbacks ( void *  classPtr,
void(*)(void *, int, int progressCallback,
void(*)(void *, int, const char *)  initCallback,
void(*)(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 statsUpdatedCallback,
void(*)(void *, int, const char *, const char *)  cameraInfoCallback 
)

Definition at line 331 of file RTABMapApp.cpp.

◆ SetViewPort()

void RTABMapApp::SetViewPort ( int  width,
int  height 
)

Definition at line 1164 of file RTABMapApp.cpp.

◆ setWireframe()

void RTABMapApp::setWireframe ( bool  enabled)

Definition at line 2925 of file RTABMapApp.cpp.

◆ showMeasures()

void RTABMapApp::showMeasures ( bool  x,
bool  y,
bool  z,
bool  custom 
)

◆ smoothMesh()

bool RTABMapApp::smoothMesh ( int  id,
rtabmap::Mesh mesh 
)
private

Definition at line 1195 of file RTABMapApp.cpp.

◆ startCamera()

bool RTABMapApp::startCamera ( )

Definition at line 930 of file RTABMapApp.cpp.

◆ stopCamera()

void RTABMapApp::stopCamera ( )

Definition at line 1023 of file RTABMapApp.cpp.

◆ teleportButtonClicked()

void RTABMapApp::teleportButtonClicked ( )

Definition at line 4429 of file RTABMapApp.cpp.

◆ updateMeasuringState()

void RTABMapApp::updateMeasuringState ( )
private

Definition at line 2450 of file RTABMapApp.cpp.

◆ updateMeshDecimation()

int RTABMapApp::updateMeshDecimation ( int  width,
int  height 
)
private

Definition at line 827 of file RTABMapApp.cpp.

◆ writeExportedMesh()

bool RTABMapApp::writeExportedMesh ( const std::string directory,
const std::string name 
)

Definition at line 4171 of file RTABMapApp.cpp.

Member Data Documentation

◆ addMeasureClicked_

bool RTABMapApp::addMeasureClicked_
private

Definition at line 291 of file RTABMapApp.h.

◆ appendMode_

bool RTABMapApp::appendMode_
private

Definition at line 241 of file RTABMapApp.h.

◆ backgroundColor_

float RTABMapApp::backgroundColor_
private

Definition at line 252 of file RTABMapApp.h.

◆ bilateralFilteringOnNextRender_

bool RTABMapApp::bilateralFilteringOnNextRender_
private

Definition at line 266 of file RTABMapApp.h.

◆ bufferedStatsData_

std::map<std::string, float> RTABMapApp::bufferedStatsData_
private

Definition at line 275 of file RTABMapApp.h.

◆ camera_

rtabmap::CameraMobile* RTABMapApp::camera_
private

Definition at line 225 of file RTABMapApp.h.

◆ cameraColor_

bool RTABMapApp::cameraColor_
private

Definition at line 239 of file RTABMapApp.h.

◆ cameraDriver_

int RTABMapApp::cameraDriver_
private

Definition at line 224 of file RTABMapApp.h.

◆ cameraJustInitialized_

bool RTABMapApp::cameraJustInitialized_
private

Definition at line 268 of file RTABMapApp.h.

◆ cameraMutex_

boost::mutex RTABMapApp::cameraMutex_
private

Definition at line 311 of file RTABMapApp.h.

◆ clearSceneOnNextRender_

bool RTABMapApp::clearSceneOnNextRender_
private

Definition at line 260 of file RTABMapApp.h.

◆ cloudDensityLevel_

int RTABMapApp::cloudDensityLevel_
private

Definition at line 245 of file RTABMapApp.h.

◆ clusterRatio_

float RTABMapApp::clusterRatio_
private

Definition at line 249 of file RTABMapApp.h.

◆ createdMeshes_

std::map<int, rtabmap::Mesh> RTABMapApp::createdMeshes_
private

Definition at line 320 of file RTABMapApp.h.

◆ dataRecorderMode_

bool RTABMapApp::dataRecorderMode_
private

Definition at line 259 of file RTABMapApp.h.

◆ depthConfidence_

int RTABMapApp::depthConfidence_
private

Definition at line 253 of file RTABMapApp.h.

◆ depthFromMotion_

bool RTABMapApp::depthFromMotion_
private

Definition at line 238 of file RTABMapApp.h.

◆ exportedMeshUpdated_

bool RTABMapApp::exportedMeshUpdated_
private

Definition at line 278 of file RTABMapApp.h.

◆ exporting_

bool RTABMapApp::exporting_
private

Definition at line 262 of file RTABMapApp.h.

◆ exportPointCloudFormat_

std::string RTABMapApp::exportPointCloudFormat_
private

Definition at line 255 of file RTABMapApp.h.

◆ filterPolygonsOnNextRender_

bool RTABMapApp::filterPolygonsOnNextRender_
private

Definition at line 264 of file RTABMapApp.h.

◆ fpsTime_

UTimer RTABMapApp::fpsTime_
private

Definition at line 303 of file RTABMapApp.h.

◆ fullResolution_

bool RTABMapApp::fullResolution_
private

Definition at line 240 of file RTABMapApp.h.

◆ gainCompensationOnNextRender_

int RTABMapApp::gainCompensationOnNextRender_
private

Definition at line 265 of file RTABMapApp.h.

◆ graphOptimization_

bool RTABMapApp::graphOptimization_
private

Definition at line 232 of file RTABMapApp.h.

◆ lastDrawnCloudsCount_

int RTABMapApp::lastDrawnCloudsCount_
private

Definition at line 271 of file RTABMapApp.h.

◆ lastPoseEventTime_

double RTABMapApp::lastPoseEventTime_
private

Definition at line 274 of file RTABMapApp.h.

◆ lastPostRenderEventTime_

double RTABMapApp::lastPostRenderEventTime_
private

Definition at line 273 of file RTABMapApp.h.

◆ localizationMode_

bool RTABMapApp::localizationMode_
private

Definition at line 234 of file RTABMapApp.h.

◆ logHandler_

rtabmap::LogHandler* RTABMapApp::logHandler_
private

Definition at line 229 of file RTABMapApp.h.

◆ main_scene_

Scene RTABMapApp::main_scene_
private

Definition at line 301 of file RTABMapApp.h.

◆ mappingParameters_

rtabmap::ParametersMap RTABMapApp::mappingParameters_
private

Definition at line 257 of file RTABMapApp.h.

◆ mapToOdom_

rtabmap::Transform RTABMapApp::mapToOdom_
private

Definition at line 309 of file RTABMapApp.h.

◆ maxCloudDepth_

float RTABMapApp::maxCloudDepth_
private

Definition at line 243 of file RTABMapApp.h.

◆ maxGainRadius_

float RTABMapApp::maxGainRadius_
private

Definition at line 250 of file RTABMapApp.h.

◆ measures_

std::list<Measure> RTABMapApp::measures_
private

Definition at line 284 of file RTABMapApp.h.

◆ measuresUpdated_

bool RTABMapApp::measuresUpdated_
private

Definition at line 285 of file RTABMapApp.h.

◆ measuringMode_

int RTABMapApp::measuringMode_
private

Definition at line 290 of file RTABMapApp.h.

◆ measuringTextSize_

float RTABMapApp::measuringTextSize_
private

Definition at line 287 of file RTABMapApp.h.

◆ measuringTmpNormals_

std::vector<cv::Point3f> RTABMapApp::measuringTmpNormals_
private

Definition at line 295 of file RTABMapApp.h.

◆ measuringTmpPts_

std::vector<cv::Point3f> RTABMapApp::measuringTmpPts_
private

Definition at line 294 of file RTABMapApp.h.

◆ meshAngleToleranceDeg_

float RTABMapApp::meshAngleToleranceDeg_
private

Definition at line 247 of file RTABMapApp.h.

◆ meshDecimationFactor_

float RTABMapApp::meshDecimationFactor_
private

Definition at line 248 of file RTABMapApp.h.

◆ meshesMutex_

boost::mutex RTABMapApp::meshesMutex_
private

Definition at line 313 of file RTABMapApp.h.

◆ meshTrianglePix_

int RTABMapApp::meshTrianglePix_
private

Definition at line 246 of file RTABMapApp.h.

◆ metricSystem_

bool RTABMapApp::metricSystem_
private

Definition at line 286 of file RTABMapApp.h.

◆ minCloudDepth_

float RTABMapApp::minCloudDepth_
private

Definition at line 244 of file RTABMapApp.h.

◆ nodesFiltering_

bool RTABMapApp::nodesFiltering_
private

Definition at line 233 of file RTABMapApp.h.

◆ odomCloudShown_

bool RTABMapApp::odomCloudShown_
private

Definition at line 231 of file RTABMapApp.h.

◆ openingDatabase_

bool RTABMapApp::openingDatabase_
private

Definition at line 261 of file RTABMapApp.h.

◆ optMesh_

rtabmap::Mesh RTABMapApp::optMesh_
private

Definition at line 281 of file RTABMapApp.h.

◆ optRefId_

int RTABMapApp::optRefId_
private

Definition at line 282 of file RTABMapApp.h.

◆ optRefPose_

rtabmap::Transform* RTABMapApp::optRefPose_
private

Definition at line 283 of file RTABMapApp.h.

◆ optTexture_

cv::Mat RTABMapApp::optTexture_
private

Definition at line 280 of file RTABMapApp.h.

◆ optTextureMesh_

pcl::TextureMesh::Ptr RTABMapApp::optTextureMesh_
private

Definition at line 279 of file RTABMapApp.h.

◆ poseEvents_

std::list<rtabmap::Transform> RTABMapApp::poseEvents_
private

Definition at line 307 of file RTABMapApp.h.

◆ poseMutex_

boost::mutex RTABMapApp::poseMutex_
private

Definition at line 315 of file RTABMapApp.h.

◆ postProcessing_

bool RTABMapApp::postProcessing_
private

Definition at line 263 of file RTABMapApp.h.

◆ progressionStatus_

rtabmap::ProgressionStatus RTABMapApp::progressionStatus_
private

Definition at line 325 of file RTABMapApp.h.

◆ quadSample_

pcl::PointCloud<pcl::PointXYZ>::Ptr RTABMapApp::quadSample_
private

Definition at line 297 of file RTABMapApp.h.

◆ quadSamplePolygons_

std::vector<pcl::Vertices> RTABMapApp::quadSamplePolygons_
private

Definition at line 298 of file RTABMapApp.h.

◆ rawPoses_

std::map<int, rtabmap::Transform> RTABMapApp::rawPoses_
private

Definition at line 321 of file RTABMapApp.h.

◆ rawScanSaved_

bool RTABMapApp::rawScanSaved_
private

Definition at line 236 of file RTABMapApp.h.

◆ removeMeasureClicked_

bool RTABMapApp::removeMeasureClicked_
private

Definition at line 293 of file RTABMapApp.h.

◆ renderingMutex_

boost::mutex RTABMapApp::renderingMutex_
private

Definition at line 316 of file RTABMapApp.h.

◆ renderingTextureDecimation_

int RTABMapApp::renderingTextureDecimation_
private

Definition at line 251 of file RTABMapApp.h.

◆ renderingTime_

float RTABMapApp::renderingTime_
private

Definition at line 272 of file RTABMapApp.h.

◆ rtabmap_

rtabmap::Rtabmap* RTABMapApp::rtabmap_
private

Definition at line 228 of file RTABMapApp.h.

◆ rtabmapEvents_

std::list<rtabmap::RtabmapEvent*> RTABMapApp::rtabmapEvents_
private

Definition at line 305 of file RTABMapApp.h.

◆ rtabmapMutex_

boost::mutex RTABMapApp::rtabmapMutex_
private

Definition at line 312 of file RTABMapApp.h.

◆ rtabmapThread_

rtabmap::RtabmapThread* RTABMapApp::rtabmapThread_
private

Definition at line 227 of file RTABMapApp.h.

◆ screenshotReady_

USemaphore RTABMapApp::screenshotReady_
private

Definition at line 318 of file RTABMapApp.h.

◆ sensorCaptureThread_

rtabmap::SensorCaptureThread* RTABMapApp::sensorCaptureThread_
private

Definition at line 226 of file RTABMapApp.h.

◆ sensorEvents_

std::list<rtabmap::SensorEvent> RTABMapApp::sensorEvents_
private

Definition at line 306 of file RTABMapApp.h.

◆ sensorMutex_

boost::mutex RTABMapApp::sensorMutex_
private

Definition at line 314 of file RTABMapApp.h.

◆ smoothing_

bool RTABMapApp::smoothing_
private

Definition at line 237 of file RTABMapApp.h.

◆ snapAxes_

std::vector<cv::Vec3f> RTABMapApp::snapAxes_
private

Definition at line 289 of file RTABMapApp.h.

◆ snapAxisThr_

float RTABMapApp::snapAxisThr_
private

Definition at line 288 of file RTABMapApp.h.

◆ status_

std::pair<rtabmap::RtabmapEventInit::Status, std::string> RTABMapApp::status_
private

Definition at line 323 of file RTABMapApp.h.

◆ swiftCameraInfoEventCallback

void(* RTABMapApp::swiftCameraInfoEventCallback) (void *, int, const char *, const char *)
private

Definition at line 341 of file RTABMapApp.h.

◆ swiftClassPtr_

void* RTABMapApp::swiftClassPtr_
private

Definition at line 328 of file RTABMapApp.h.

◆ swiftInitCallback

void(* RTABMapApp::swiftInitCallback) (void *, int, const char *)
private

Definition at line 329 of file RTABMapApp.h.

◆ swiftStatsUpdatedCallback

void(* RTABMapApp::swiftStatsUpdatedCallback) (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)
private

Definition at line 330 of file RTABMapApp.h.

◆ takeScreenshotOnNextRender_

bool RTABMapApp::takeScreenshotOnNextRender_
private

Definition at line 267 of file RTABMapApp.h.

◆ targetPoint_

pcl::PointCloud<pcl::PointXYZRGB>::Ptr RTABMapApp::targetPoint_
private

Definition at line 296 of file RTABMapApp.h.

◆ teleportClicked_

bool RTABMapApp::teleportClicked_
private

Definition at line 292 of file RTABMapApp.h.

◆ totalPoints_

int RTABMapApp::totalPoints_
private

Definition at line 269 of file RTABMapApp.h.

◆ totalPolygons_

int RTABMapApp::totalPolygons_
private

Definition at line 270 of file RTABMapApp.h.

◆ trajectoryMode_

bool RTABMapApp::trajectoryMode_
private

Definition at line 235 of file RTABMapApp.h.

◆ upstreamRelocalizationMaxAcc_

float RTABMapApp::upstreamRelocalizationMaxAcc_
private

Definition at line 254 of file RTABMapApp.h.

◆ useExternalLidar_

bool RTABMapApp::useExternalLidar_
private

Definition at line 242 of file RTABMapApp.h.

◆ visualizingMesh_

bool RTABMapApp::visualizingMesh_
private

Definition at line 277 of file RTABMapApp.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:46:09