#include <RTABMapApp.h>
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 () | |
![]() | |
void | registerToEventsManager () |
void | unregisterFromEventsManager () |
![]() | |
UEventsSender () | |
virtual | ~UEventsSender () |
Protected Member Functions | |
virtual bool | handleEvent (UEvent *event) |
![]() | |
UEventsHandler () | |
virtual | ~UEventsHandler () |
![]() | |
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) |
Definition at line 54 of file RTABMapApp.h.
RTABMapApp::RTABMapApp | ( | ) |
Definition at line 218 of file RTABMapApp.cpp.
RTABMapApp::~RTABMapApp | ( | ) |
Definition at line 355 of file RTABMapApp.cpp.
Definition at line 3186 of file RTABMapApp.cpp.
void RTABMapApp::addMeasureButtonClicked | ( | ) |
Definition at line 4420 of file RTABMapApp.cpp.
void RTABMapApp::cancelProcessing | ( | ) |
Definition at line 3270 of file RTABMapApp.cpp.
void RTABMapApp::clearMeasures | ( | ) |
Definition at line 4405 of file RTABMapApp.cpp.
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.
|
private |
Definition at line 1044 of file RTABMapApp.cpp.
|
private |
Definition at line 1111 of file RTABMapApp.cpp.
|
private |
Definition at line 1260 of file RTABMapApp.cpp.
|
private |
Definition at line 129 of file RTABMapApp.cpp.
|
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.
Implements UEventsHandler.
Definition at line 4705 of file RTABMapApp.cpp.
void RTABMapApp::InitializeGLContent | ( | ) |
Definition at line 1154 of file RTABMapApp.cpp.
bool RTABMapApp::isBuiltWith | ( | int | cameraDriver | ) | const |
Definition at line 896 of file RTABMapApp.cpp.
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.
int RTABMapApp::openDatabase | ( | const std::string & | databasePath, |
bool | databaseInMemory, | ||
bool | optimize, | ||
bool | clearDatabase | ||
) |
Definition at line 392 of file RTABMapApp.cpp.
bool RTABMapApp::postExportation | ( | bool | visualize | ) |
Definition at line 4093 of file RTABMapApp.cpp.
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.
Definition at line 4306 of file RTABMapApp.cpp.
bool RTABMapApp::recover | ( | const std::string & | from, |
const std::string & | to | ||
) |
Definition at line 3250 of file RTABMapApp.cpp.
void RTABMapApp::removeMeasure | ( | ) |
Definition at line 4438 of file RTABMapApp.cpp.
int RTABMapApp::Render | ( | ) |
Definition at line 1316 of file RTABMapApp.cpp.
void RTABMapApp::save | ( | const std::string & | databasePath | ) |
Definition at line 3195 of file RTABMapApp.cpp.
void RTABMapApp::setAppendMode | ( | bool | enabled | ) |
Definition at line 3026 of file RTABMapApp.cpp.
void RTABMapApp::setBackfaceCulling | ( | bool | enabled | ) |
Definition at line 2921 of file RTABMapApp.cpp.
void RTABMapApp::setBackgroundColor | ( | float | gray | ) |
Definition at line 3100 of file RTABMapApp.cpp.
void RTABMapApp::setCameraColor | ( | bool | enabled | ) |
Definition at line 2994 of file RTABMapApp.cpp.
void RTABMapApp::SetCameraType | ( | tango_gl::GestureCamera::CameraType | camera_type | ) |
Definition at line 2839 of file RTABMapApp.cpp.
void RTABMapApp::setCloudDensityLevel | ( | int | value | ) |
Definition at line 3064 of file RTABMapApp.cpp.
void RTABMapApp::setClusterRatio | ( | float | value | ) |
Definition at line 3084 of file RTABMapApp.cpp.
void RTABMapApp::setDataRecorderMode | ( | bool | enabled | ) |
Definition at line 3042 of file RTABMapApp.cpp.
void RTABMapApp::setDepthConfidence | ( | int | value | ) |
Definition at line 3108 of file RTABMapApp.cpp.
void RTABMapApp::setDepthFromMotion | ( | bool | enabled | ) |
Definition at line 3018 of file RTABMapApp.cpp.
void RTABMapApp::setExportPointCloudFormat | ( | const std::string & | format | ) |
Definition at line 3117 of file RTABMapApp.cpp.
void RTABMapApp::setFOV | ( | float | angle | ) |
Definition at line 2896 of file RTABMapApp.cpp.
void RTABMapApp::setFullResolution | ( | bool | enabled | ) |
Definition at line 3002 of file RTABMapApp.cpp.
void RTABMapApp::setGPS | ( | const rtabmap::GPS & | gps | ) |
Definition at line 3177 of file RTABMapApp.cpp.
void RTABMapApp::setGraphOptimization | ( | bool | enabled | ) |
Definition at line 2948 of file RTABMapApp.cpp.
void RTABMapApp::setGraphVisible | ( | bool | visible | ) |
Definition at line 2975 of file RTABMapApp.cpp.
void RTABMapApp::setGridRotation | ( | float | value | ) |
Definition at line 2904 of file RTABMapApp.cpp.
void RTABMapApp::setGridVisible | ( | bool | visible | ) |
Definition at line 2981 of file RTABMapApp.cpp.
void RTABMapApp::setLighting | ( | bool | enabled | ) |
Definition at line 2917 of file RTABMapApp.cpp.
void RTABMapApp::setLocalizationMode | ( | bool | enabled | ) |
Definition at line 2934 of file RTABMapApp.cpp.
void RTABMapApp::setMapCloudShown | ( | bool | shown | ) |
Definition at line 2879 of file RTABMapApp.cpp.
int RTABMapApp::setMappingParameter | ( | const std::string & | key, |
const std::string & | value | ||
) |
Definition at line 3133 of file RTABMapApp.cpp.
void RTABMapApp::setMaxCloudDepth | ( | float | value | ) |
Definition at line 3054 of file RTABMapApp.cpp.
void RTABMapApp::setMaxGainRadius | ( | float | value | ) |
Definition at line 3089 of file RTABMapApp.cpp.
void RTABMapApp::setMeasuringMode | ( | int | mode | ) |
Definition at line 4412 of file RTABMapApp.cpp.
void RTABMapApp::setMeasuringTextSize | ( | float | size | ) |
Definition at line 4456 of file RTABMapApp.cpp.
void RTABMapApp::setMeshAngleTolerance | ( | float | value | ) |
Definition at line 3069 of file RTABMapApp.cpp.
void RTABMapApp::setMeshDecimationFactor | ( | float | value | ) |
Definition at line 3074 of file RTABMapApp.cpp.
void RTABMapApp::setMeshRendering | ( | bool | enabled, |
bool | withTexture | ||
) |
Definition at line 2888 of file RTABMapApp.cpp.
void RTABMapApp::setMeshTriangleSize | ( | int | value | ) |
Definition at line 3079 of file RTABMapApp.cpp.
void RTABMapApp::setMetricSystem | ( | bool | enabled | ) |
Definition at line 4447 of file RTABMapApp.cpp.
void RTABMapApp::setMinCloudDepth | ( | float | value | ) |
Definition at line 3059 of file RTABMapApp.cpp.
void RTABMapApp::setNodesFiltering | ( | bool | enabled | ) |
Definition at line 2970 of file RTABMapApp.cpp.
void RTABMapApp::setOdomCloudShown | ( | bool | shown | ) |
Definition at line 2883 of file RTABMapApp.cpp.
void RTABMapApp::setOnlineBlending | ( | bool | enabled | ) |
Definition at line 2875 of file RTABMapApp.cpp.
void RTABMapApp::setOrthoCropFactor | ( | float | value | ) |
Definition at line 2900 of file RTABMapApp.cpp.
void RTABMapApp::setPausedMapping | ( | bool | paused | ) |
Definition at line 2850 of file RTABMapApp.cpp.
void RTABMapApp::setPointSize | ( | float | value | ) |
Definition at line 2892 of file RTABMapApp.cpp.
void RTABMapApp::setRawScanSaved | ( | bool | enabled | ) |
Definition at line 2986 of file RTABMapApp.cpp.
void RTABMapApp::setRenderingTextureDecimation | ( | int | value | ) |
Definition at line 3094 of file RTABMapApp.cpp.
Definition at line 379 of file RTABMapApp.cpp.
void RTABMapApp::setSmoothing | ( | bool | enabled | ) |
Definition at line 3010 of file RTABMapApp.cpp.
void RTABMapApp::setTextureColorSeamsHidden | ( | bool | hidden | ) |
Definition at line 2929 of file RTABMapApp.cpp.
void RTABMapApp::setTrajectoryMode | ( | bool | enabled | ) |
Definition at line 2942 of file RTABMapApp.cpp.
void RTABMapApp::setUpstreamRelocalizationAccThr | ( | float | value | ) |
Definition at line 3037 of file RTABMapApp.cpp.
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.
Definition at line 1164 of file RTABMapApp.cpp.
void RTABMapApp::setWireframe | ( | bool | enabled | ) |
Definition at line 2925 of file RTABMapApp.cpp.
void RTABMapApp::showMeasures | ( | bool | x, |
bool | y, | ||
bool | z, | ||
bool | custom | ||
) |
|
private |
Definition at line 1195 of file RTABMapApp.cpp.
bool RTABMapApp::startCamera | ( | ) |
Definition at line 930 of file RTABMapApp.cpp.
void RTABMapApp::stopCamera | ( | ) |
Definition at line 1023 of file RTABMapApp.cpp.
void RTABMapApp::teleportButtonClicked | ( | ) |
Definition at line 4429 of file RTABMapApp.cpp.
|
private |
Definition at line 2450 of file RTABMapApp.cpp.
Definition at line 827 of file RTABMapApp.cpp.
bool RTABMapApp::writeExportedMesh | ( | const std::string & | directory, |
const std::string & | name | ||
) |
Definition at line 4171 of file RTABMapApp.cpp.
|
private |
Definition at line 291 of file RTABMapApp.h.
|
private |
Definition at line 241 of file RTABMapApp.h.
|
private |
Definition at line 252 of file RTABMapApp.h.
|
private |
Definition at line 266 of file RTABMapApp.h.
|
private |
Definition at line 275 of file RTABMapApp.h.
|
private |
Definition at line 225 of file RTABMapApp.h.
|
private |
Definition at line 239 of file RTABMapApp.h.
|
private |
Definition at line 224 of file RTABMapApp.h.
|
private |
Definition at line 268 of file RTABMapApp.h.
|
private |
Definition at line 311 of file RTABMapApp.h.
|
private |
Definition at line 260 of file RTABMapApp.h.
|
private |
Definition at line 245 of file RTABMapApp.h.
|
private |
Definition at line 249 of file RTABMapApp.h.
|
private |
Definition at line 320 of file RTABMapApp.h.
|
private |
Definition at line 259 of file RTABMapApp.h.
|
private |
Definition at line 253 of file RTABMapApp.h.
|
private |
Definition at line 238 of file RTABMapApp.h.
|
private |
Definition at line 278 of file RTABMapApp.h.
|
private |
Definition at line 262 of file RTABMapApp.h.
|
private |
Definition at line 255 of file RTABMapApp.h.
|
private |
Definition at line 264 of file RTABMapApp.h.
|
private |
Definition at line 303 of file RTABMapApp.h.
|
private |
Definition at line 240 of file RTABMapApp.h.
|
private |
Definition at line 265 of file RTABMapApp.h.
|
private |
Definition at line 232 of file RTABMapApp.h.
|
private |
Definition at line 271 of file RTABMapApp.h.
|
private |
Definition at line 274 of file RTABMapApp.h.
|
private |
Definition at line 273 of file RTABMapApp.h.
|
private |
Definition at line 234 of file RTABMapApp.h.
|
private |
Definition at line 229 of file RTABMapApp.h.
|
private |
Definition at line 301 of file RTABMapApp.h.
|
private |
Definition at line 257 of file RTABMapApp.h.
|
private |
Definition at line 309 of file RTABMapApp.h.
|
private |
Definition at line 243 of file RTABMapApp.h.
|
private |
Definition at line 250 of file RTABMapApp.h.
|
private |
Definition at line 284 of file RTABMapApp.h.
|
private |
Definition at line 285 of file RTABMapApp.h.
|
private |
Definition at line 290 of file RTABMapApp.h.
|
private |
Definition at line 287 of file RTABMapApp.h.
|
private |
Definition at line 295 of file RTABMapApp.h.
|
private |
Definition at line 294 of file RTABMapApp.h.
|
private |
Definition at line 247 of file RTABMapApp.h.
|
private |
Definition at line 248 of file RTABMapApp.h.
|
private |
Definition at line 313 of file RTABMapApp.h.
|
private |
Definition at line 246 of file RTABMapApp.h.
|
private |
Definition at line 286 of file RTABMapApp.h.
|
private |
Definition at line 244 of file RTABMapApp.h.
|
private |
Definition at line 233 of file RTABMapApp.h.
|
private |
Definition at line 231 of file RTABMapApp.h.
|
private |
Definition at line 261 of file RTABMapApp.h.
|
private |
Definition at line 281 of file RTABMapApp.h.
|
private |
Definition at line 282 of file RTABMapApp.h.
|
private |
Definition at line 283 of file RTABMapApp.h.
|
private |
Definition at line 280 of file RTABMapApp.h.
|
private |
Definition at line 279 of file RTABMapApp.h.
|
private |
Definition at line 307 of file RTABMapApp.h.
|
private |
Definition at line 315 of file RTABMapApp.h.
|
private |
Definition at line 263 of file RTABMapApp.h.
|
private |
Definition at line 325 of file RTABMapApp.h.
|
private |
Definition at line 297 of file RTABMapApp.h.
|
private |
Definition at line 298 of file RTABMapApp.h.
|
private |
Definition at line 321 of file RTABMapApp.h.
|
private |
Definition at line 236 of file RTABMapApp.h.
|
private |
Definition at line 293 of file RTABMapApp.h.
|
private |
Definition at line 316 of file RTABMapApp.h.
|
private |
Definition at line 251 of file RTABMapApp.h.
|
private |
Definition at line 272 of file RTABMapApp.h.
|
private |
Definition at line 228 of file RTABMapApp.h.
|
private |
Definition at line 305 of file RTABMapApp.h.
|
private |
Definition at line 312 of file RTABMapApp.h.
|
private |
Definition at line 227 of file RTABMapApp.h.
|
private |
Definition at line 318 of file RTABMapApp.h.
|
private |
Definition at line 226 of file RTABMapApp.h.
|
private |
Definition at line 306 of file RTABMapApp.h.
|
private |
Definition at line 314 of file RTABMapApp.h.
|
private |
Definition at line 237 of file RTABMapApp.h.
|
private |
Definition at line 289 of file RTABMapApp.h.
|
private |
Definition at line 288 of file RTABMapApp.h.
|
private |
Definition at line 323 of file RTABMapApp.h.
|
private |
Definition at line 341 of file RTABMapApp.h.
|
private |
Definition at line 328 of file RTABMapApp.h.
|
private |
Definition at line 329 of file RTABMapApp.h.
|
private |
Definition at line 330 of file RTABMapApp.h.
|
private |
Definition at line 267 of file RTABMapApp.h.
|
private |
Definition at line 296 of file RTABMapApp.h.
|
private |
Definition at line 292 of file RTABMapApp.h.
|
private |
Definition at line 269 of file RTABMapApp.h.
|
private |
Definition at line 270 of file RTABMapApp.h.
|
private |
Definition at line 235 of file RTABMapApp.h.
|
private |
Definition at line 254 of file RTABMapApp.h.
|
private |
Definition at line 242 of file RTABMapApp.h.
|
private |
Definition at line 277 of file RTABMapApp.h.