#include <RTABMapApp.h>
Public Member Functions | |
void | addEnvSensor (int type, float value) |
void | cancelProcessing () |
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) |
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) |
void | postCameraPoseEvent (float x, float y, float z, float qx, float qy, float qz, float qw, double stamp) |
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, 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) |
int | postProcessing (int approach) |
bool | recover (const std::string &from, const std::string &to) |
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 | 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 | setMeshAngleTolerance (float value) |
void | setMeshDecimationFactor (float value) |
void | setMeshRendering (bool enabled, bool withTexture) |
void | setMeshTriangleSize (int value) |
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 | setTrajectoryMode (bool enabled) |
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 | SetViewPort (int width, int height) |
void | setWireframe (bool enabled) |
bool | startCamera () |
void | stopCamera () |
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) |
int | updateMeshDecimation (int width, int height) |
Definition at line 53 of file RTABMapApp.h.
RTABMapApp::RTABMapApp | ( | ) |
Definition at line 203 of file RTABMapApp.cpp.
RTABMapApp::~RTABMapApp | ( | ) |
Definition at line 319 of file RTABMapApp.cpp.
Definition at line 2548 of file RTABMapApp.cpp.
void RTABMapApp::cancelProcessing | ( | ) |
Definition at line 2629 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, | ||
bool | blockRendering | ||
) |
Definition at line 2635 of file RTABMapApp.cpp.
|
private |
Definition at line 983 of file RTABMapApp.cpp.
|
private |
Definition at line 1050 of file RTABMapApp.cpp.
|
private |
Definition at line 1199 of file RTABMapApp.cpp.
|
private |
Definition at line 124 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 3964 of file RTABMapApp.cpp.
void RTABMapApp::InitializeGLContent | ( | ) |
Definition at line 1093 of file RTABMapApp.cpp.
bool RTABMapApp::isBuiltWith | ( | int | cameraDriver | ) | const |
Definition at line 843 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 2240 of file RTABMapApp.cpp.
int RTABMapApp::openDatabase | ( | const std::string & | databasePath, |
bool | databaseInMemory, | ||
bool | optimize, | ||
bool | clearDatabase | ||
) |
Definition at line 356 of file RTABMapApp.cpp.
void RTABMapApp::postCameraPoseEvent | ( | float | x, |
float | y, | ||
float | z, | ||
float | qx, | ||
float | qy, | ||
float | qz, | ||
float | qw, | ||
double | stamp | ||
) |
Definition at line 3715 of file RTABMapApp.cpp.
bool RTABMapApp::postExportation | ( | bool | visualize | ) |
Definition at line 3430 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, | ||
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 | ||
) |
Definition at line 3733 of file RTABMapApp.cpp.
Definition at line 3616 of file RTABMapApp.cpp.
bool RTABMapApp::recover | ( | const std::string & | from, |
const std::string & | to | ||
) |
Definition at line 2609 of file RTABMapApp.cpp.
int RTABMapApp::Render | ( | ) |
Definition at line 1255 of file RTABMapApp.cpp.
void RTABMapApp::save | ( | const std::string & | databasePath | ) |
Definition at line 2557 of file RTABMapApp.cpp.
void RTABMapApp::setAppendMode | ( | bool | enabled | ) |
Definition at line 2409 of file RTABMapApp.cpp.
void RTABMapApp::setBackfaceCulling | ( | bool | enabled | ) |
Definition at line 2308 of file RTABMapApp.cpp.
void RTABMapApp::setBackgroundColor | ( | float | gray | ) |
Definition at line 2478 of file RTABMapApp.cpp.
void RTABMapApp::setCameraColor | ( | bool | enabled | ) |
Definition at line 2377 of file RTABMapApp.cpp.
void RTABMapApp::SetCameraType | ( | tango_gl::GestureCamera::CameraType | camera_type | ) |
Definition at line 2235 of file RTABMapApp.cpp.
void RTABMapApp::setCloudDensityLevel | ( | int | value | ) |
Definition at line 2442 of file RTABMapApp.cpp.
void RTABMapApp::setClusterRatio | ( | float | value | ) |
Definition at line 2462 of file RTABMapApp.cpp.
void RTABMapApp::setDataRecorderMode | ( | bool | enabled | ) |
Definition at line 2420 of file RTABMapApp.cpp.
void RTABMapApp::setDepthConfidence | ( | int | value | ) |
Definition at line 2486 of file RTABMapApp.cpp.
void RTABMapApp::setDepthFromMotion | ( | bool | enabled | ) |
Definition at line 2401 of file RTABMapApp.cpp.
void RTABMapApp::setFOV | ( | float | angle | ) |
Definition at line 2292 of file RTABMapApp.cpp.
void RTABMapApp::setFullResolution | ( | bool | enabled | ) |
Definition at line 2385 of file RTABMapApp.cpp.
void RTABMapApp::setGPS | ( | const rtabmap::GPS & | gps | ) |
Definition at line 2539 of file RTABMapApp.cpp.
void RTABMapApp::setGraphOptimization | ( | bool | enabled | ) |
Definition at line 2331 of file RTABMapApp.cpp.
void RTABMapApp::setGraphVisible | ( | bool | visible | ) |
Definition at line 2358 of file RTABMapApp.cpp.
void RTABMapApp::setGridRotation | ( | float | value | ) |
Definition at line 2300 of file RTABMapApp.cpp.
void RTABMapApp::setGridVisible | ( | bool | visible | ) |
Definition at line 2364 of file RTABMapApp.cpp.
void RTABMapApp::setLighting | ( | bool | enabled | ) |
Definition at line 2304 of file RTABMapApp.cpp.
void RTABMapApp::setLocalizationMode | ( | bool | enabled | ) |
Definition at line 2317 of file RTABMapApp.cpp.
void RTABMapApp::setMapCloudShown | ( | bool | shown | ) |
Definition at line 2275 of file RTABMapApp.cpp.
int RTABMapApp::setMappingParameter | ( | const std::string & | key, |
const std::string & | value | ||
) |
Definition at line 2495 of file RTABMapApp.cpp.
void RTABMapApp::setMaxCloudDepth | ( | float | value | ) |
Definition at line 2432 of file RTABMapApp.cpp.
void RTABMapApp::setMaxGainRadius | ( | float | value | ) |
Definition at line 2467 of file RTABMapApp.cpp.
void RTABMapApp::setMeshAngleTolerance | ( | float | value | ) |
Definition at line 2447 of file RTABMapApp.cpp.
void RTABMapApp::setMeshDecimationFactor | ( | float | value | ) |
Definition at line 2452 of file RTABMapApp.cpp.
void RTABMapApp::setMeshRendering | ( | bool | enabled, |
bool | withTexture | ||
) |
Definition at line 2284 of file RTABMapApp.cpp.
void RTABMapApp::setMeshTriangleSize | ( | int | value | ) |
Definition at line 2457 of file RTABMapApp.cpp.
void RTABMapApp::setMinCloudDepth | ( | float | value | ) |
Definition at line 2437 of file RTABMapApp.cpp.
void RTABMapApp::setNodesFiltering | ( | bool | enabled | ) |
Definition at line 2353 of file RTABMapApp.cpp.
void RTABMapApp::setOdomCloudShown | ( | bool | shown | ) |
Definition at line 2279 of file RTABMapApp.cpp.
void RTABMapApp::setOnlineBlending | ( | bool | enabled | ) |
Definition at line 2271 of file RTABMapApp.cpp.
void RTABMapApp::setOrthoCropFactor | ( | float | value | ) |
Definition at line 2296 of file RTABMapApp.cpp.
void RTABMapApp::setPausedMapping | ( | bool | paused | ) |
Definition at line 2246 of file RTABMapApp.cpp.
void RTABMapApp::setPointSize | ( | float | value | ) |
Definition at line 2288 of file RTABMapApp.cpp.
void RTABMapApp::setRawScanSaved | ( | bool | enabled | ) |
Definition at line 2369 of file RTABMapApp.cpp.
void RTABMapApp::setRenderingTextureDecimation | ( | int | value | ) |
Definition at line 2472 of file RTABMapApp.cpp.
Definition at line 343 of file RTABMapApp.cpp.
void RTABMapApp::setSmoothing | ( | bool | enabled | ) |
Definition at line 2393 of file RTABMapApp.cpp.
void RTABMapApp::setTrajectoryMode | ( | bool | enabled | ) |
Definition at line 2325 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 | ||
) |
Definition at line 297 of file RTABMapApp.cpp.
Definition at line 1103 of file RTABMapApp.cpp.
void RTABMapApp::setWireframe | ( | bool | enabled | ) |
Definition at line 2312 of file RTABMapApp.cpp.
|
private |
Definition at line 1134 of file RTABMapApp.cpp.
bool RTABMapApp::startCamera | ( | ) |
Definition at line 877 of file RTABMapApp.cpp.
void RTABMapApp::stopCamera | ( | ) |
Definition at line 963 of file RTABMapApp.cpp.
Definition at line 774 of file RTABMapApp.cpp.
bool RTABMapApp::writeExportedMesh | ( | const std::string & | directory, |
const std::string & | name | ||
) |
Definition at line 3506 of file RTABMapApp.cpp.
|
private |
Definition at line 229 of file RTABMapApp.h.
|
private |
Definition at line 240 of file RTABMapApp.h.
|
private |
Definition at line 252 of file RTABMapApp.h.
|
private |
Definition at line 261 of file RTABMapApp.h.
|
private |
Definition at line 213 of file RTABMapApp.h.
|
private |
Definition at line 227 of file RTABMapApp.h.
|
private |
Definition at line 212 of file RTABMapApp.h.
|
private |
Definition at line 254 of file RTABMapApp.h.
|
private |
Definition at line 282 of file RTABMapApp.h.
|
private |
Definition at line 246 of file RTABMapApp.h.
|
private |
Definition at line 233 of file RTABMapApp.h.
|
private |
Definition at line 237 of file RTABMapApp.h.
|
private |
Definition at line 291 of file RTABMapApp.h.
|
private |
Definition at line 245 of file RTABMapApp.h.
|
private |
Definition at line 241 of file RTABMapApp.h.
|
private |
Definition at line 226 of file RTABMapApp.h.
|
private |
Definition at line 264 of file RTABMapApp.h.
|
private |
Definition at line 248 of file RTABMapApp.h.
|
private |
Definition at line 250 of file RTABMapApp.h.
|
private |
Definition at line 274 of file RTABMapApp.h.
|
private |
Definition at line 228 of file RTABMapApp.h.
|
private |
Definition at line 251 of file RTABMapApp.h.
|
private |
Definition at line 220 of file RTABMapApp.h.
|
private |
Definition at line 257 of file RTABMapApp.h.
|
private |
Definition at line 260 of file RTABMapApp.h.
|
private |
Definition at line 259 of file RTABMapApp.h.
|
private |
Definition at line 222 of file RTABMapApp.h.
|
private |
Definition at line 217 of file RTABMapApp.h.
|
private |
Definition at line 272 of file RTABMapApp.h.
|
private |
Definition at line 243 of file RTABMapApp.h.
|
private |
Definition at line 280 of file RTABMapApp.h.
|
private |
Definition at line 231 of file RTABMapApp.h.
|
private |
Definition at line 238 of file RTABMapApp.h.
|
private |
Definition at line 235 of file RTABMapApp.h.
|
private |
Definition at line 236 of file RTABMapApp.h.
|
private |
Definition at line 284 of file RTABMapApp.h.
|
private |
Definition at line 234 of file RTABMapApp.h.
|
private |
Definition at line 232 of file RTABMapApp.h.
|
private |
Definition at line 221 of file RTABMapApp.h.
|
private |
Definition at line 219 of file RTABMapApp.h.
|
private |
Definition at line 247 of file RTABMapApp.h.
|
private |
Definition at line 265 of file RTABMapApp.h.
|
private |
Definition at line 267 of file RTABMapApp.h.
|
private |
Definition at line 268 of file RTABMapApp.h.
|
private |
Definition at line 266 of file RTABMapApp.h.
|
private |
Definition at line 278 of file RTABMapApp.h.
|
private |
Definition at line 286 of file RTABMapApp.h.
|
private |
Definition at line 249 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 224 of file RTABMapApp.h.
|
private |
Definition at line 287 of file RTABMapApp.h.
|
private |
Definition at line 239 of file RTABMapApp.h.
|
private |
Definition at line 258 of file RTABMapApp.h.
|
private |
Definition at line 216 of file RTABMapApp.h.
|
private |
Definition at line 276 of file RTABMapApp.h.
|
private |
Definition at line 283 of file RTABMapApp.h.
|
private |
Definition at line 215 of file RTABMapApp.h.
|
private |
Definition at line 289 of file RTABMapApp.h.
|
private |
Definition at line 214 of file RTABMapApp.h.
|
private |
Definition at line 277 of file RTABMapApp.h.
|
private |
Definition at line 285 of file RTABMapApp.h.
|
private |
Definition at line 225 of file RTABMapApp.h.
|
private |
Definition at line 294 of file RTABMapApp.h.
|
private |
Definition at line 299 of file RTABMapApp.h.
|
private |
Definition at line 300 of file RTABMapApp.h.
|
private |
Definition at line 301 of file RTABMapApp.h.
|
private |
Definition at line 253 of file RTABMapApp.h.
|
private |
Definition at line 255 of file RTABMapApp.h.
|
private |
Definition at line 256 of file RTABMapApp.h.
|
private |
Definition at line 223 of file RTABMapApp.h.
|
private |
Definition at line 230 of file RTABMapApp.h.
|
private |
Definition at line 263 of file RTABMapApp.h.