#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, const std::string &databaseSource=std::string()) |
void | postCameraPoseEvent (float x, float y, float z, float qx, float qy, float qz, float qw) |
bool | postExportation (bool visualize) |
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 | postProcessing (int approach) |
int | Render () |
RTABMapApp (JNIEnv *env, jobject caller_activity) | |
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 | 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 | 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 | SetViewPort (int width, int height) |
void | setWireframe (bool enabled) |
bool | startCamera (JNIEnv *env, jobject iBinder, jobject context, jobject activity, int driver) |
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) |
Definition at line 49 of file RTABMapApp.h.
RTABMapApp::RTABMapApp | ( | JNIEnv * | env, |
jobject | caller_activity | ||
) |
Definition at line 156 of file RTABMapApp.cpp.
RTABMapApp::~RTABMapApp | ( | ) |
Definition at line 234 of file RTABMapApp.cpp.
void RTABMapApp::addEnvSensor | ( | int | type, |
float | value | ||
) |
Definition at line 2270 of file RTABMapApp.cpp.
void RTABMapApp::cancelProcessing | ( | ) |
Definition at line 2330 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 2336 of file RTABMapApp.cpp.
|
private |
Definition at line 820 of file RTABMapApp.cpp.
|
private |
Definition at line 887 of file RTABMapApp.cpp.
|
private |
Definition at line 1037 of file RTABMapApp.cpp.
|
private |
Definition at line 81 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 3477 of file RTABMapApp.cpp.
void RTABMapApp::InitializeGLContent | ( | ) |
Definition at line 930 of file RTABMapApp.cpp.
bool RTABMapApp::isBuiltWith | ( | int | cameraDriver | ) | const |
Definition at line 628 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 1980 of file RTABMapApp.cpp.
int RTABMapApp::openDatabase | ( | const std::string & | databasePath, |
bool | databaseInMemory, | ||
bool | optimize, | ||
const std::string & | databaseSource = std::string() |
||
) |
Definition at line 271 of file RTABMapApp.cpp.
void RTABMapApp::postCameraPoseEvent | ( | float | x, |
float | y, | ||
float | z, | ||
float | qx, | ||
float | qy, | ||
float | qz, | ||
float | qw | ||
) |
Definition at line 3372 of file RTABMapApp.cpp.
bool RTABMapApp::postExportation | ( | bool | visualize | ) |
Definition at line 3106 of file RTABMapApp.cpp.
void RTABMapApp::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 | ||
) |
Definition at line 3384 of file RTABMapApp.cpp.
int RTABMapApp::postProcessing | ( | int | approach | ) |
Definition at line 3274 of file RTABMapApp.cpp.
int RTABMapApp::Render | ( | ) |
Definition at line 1093 of file RTABMapApp.cpp.
void RTABMapApp::save | ( | const std::string & | databasePath | ) |
Definition at line 2279 of file RTABMapApp.cpp.
void RTABMapApp::setAppendMode | ( | bool | enabled | ) |
Definition at line 2145 of file RTABMapApp.cpp.
void RTABMapApp::setBackfaceCulling | ( | bool | enabled | ) |
Definition at line 2048 of file RTABMapApp.cpp.
void RTABMapApp::setBackgroundColor | ( | float | gray | ) |
Definition at line 2209 of file RTABMapApp.cpp.
void RTABMapApp::setCameraColor | ( | bool | enabled | ) |
Definition at line 2113 of file RTABMapApp.cpp.
void RTABMapApp::SetCameraType | ( | tango_gl::GestureCamera::CameraType | camera_type | ) |
Definition at line 1975 of file RTABMapApp.cpp.
void RTABMapApp::setCloudDensityLevel | ( | int | value | ) |
Definition at line 2178 of file RTABMapApp.cpp.
void RTABMapApp::setClusterRatio | ( | float | value | ) |
Definition at line 2193 of file RTABMapApp.cpp.
void RTABMapApp::setDataRecorderMode | ( | bool | enabled | ) |
Definition at line 2156 of file RTABMapApp.cpp.
void RTABMapApp::setDepthFromMotion | ( | bool | enabled | ) |
Definition at line 2137 of file RTABMapApp.cpp.
void RTABMapApp::setFOV | ( | float | angle | ) |
Definition at line 2032 of file RTABMapApp.cpp.
void RTABMapApp::setFullResolution | ( | bool | enabled | ) |
Definition at line 2121 of file RTABMapApp.cpp.
void RTABMapApp::setGPS | ( | const rtabmap::GPS & | gps | ) |
Definition at line 2261 of file RTABMapApp.cpp.
void RTABMapApp::setGraphOptimization | ( | bool | enabled | ) |
Definition at line 2068 of file RTABMapApp.cpp.
void RTABMapApp::setGraphVisible | ( | bool | visible | ) |
Definition at line 2095 of file RTABMapApp.cpp.
void RTABMapApp::setGridRotation | ( | float | value | ) |
Definition at line 2040 of file RTABMapApp.cpp.
void RTABMapApp::setGridVisible | ( | bool | visible | ) |
Definition at line 2100 of file RTABMapApp.cpp.
void RTABMapApp::setLighting | ( | bool | enabled | ) |
Definition at line 2044 of file RTABMapApp.cpp.
void RTABMapApp::setLocalizationMode | ( | bool | enabled | ) |
Definition at line 2057 of file RTABMapApp.cpp.
void RTABMapApp::setMapCloudShown | ( | bool | shown | ) |
Definition at line 2015 of file RTABMapApp.cpp.
int RTABMapApp::setMappingParameter | ( | const std::string & | key, |
const std::string & | value | ||
) |
Definition at line 2217 of file RTABMapApp.cpp.
void RTABMapApp::setMaxCloudDepth | ( | float | value | ) |
Definition at line 2168 of file RTABMapApp.cpp.
void RTABMapApp::setMaxGainRadius | ( | float | value | ) |
Definition at line 2198 of file RTABMapApp.cpp.
void RTABMapApp::setMeshAngleTolerance | ( | float | value | ) |
Definition at line 2183 of file RTABMapApp.cpp.
void RTABMapApp::setMeshRendering | ( | bool | enabled, |
bool | withTexture | ||
) |
Definition at line 2024 of file RTABMapApp.cpp.
void RTABMapApp::setMeshTriangleSize | ( | int | value | ) |
Definition at line 2188 of file RTABMapApp.cpp.
void RTABMapApp::setMinCloudDepth | ( | float | value | ) |
Definition at line 2173 of file RTABMapApp.cpp.
void RTABMapApp::setNodesFiltering | ( | bool | enabled | ) |
Definition at line 2090 of file RTABMapApp.cpp.
void RTABMapApp::setOdomCloudShown | ( | bool | shown | ) |
Definition at line 2019 of file RTABMapApp.cpp.
void RTABMapApp::setOnlineBlending | ( | bool | enabled | ) |
Definition at line 2011 of file RTABMapApp.cpp.
void RTABMapApp::setOrthoCropFactor | ( | float | value | ) |
Definition at line 2036 of file RTABMapApp.cpp.
void RTABMapApp::setPausedMapping | ( | bool | paused | ) |
Definition at line 1986 of file RTABMapApp.cpp.
void RTABMapApp::setPointSize | ( | float | value | ) |
Definition at line 2028 of file RTABMapApp.cpp.
void RTABMapApp::setRawScanSaved | ( | bool | enabled | ) |
Definition at line 2105 of file RTABMapApp.cpp.
void RTABMapApp::setRenderingTextureDecimation | ( | int | value | ) |
Definition at line 2203 of file RTABMapApp.cpp.
void RTABMapApp::setScreenRotation | ( | int | displayRotation, |
int | cameraRotation | ||
) |
Definition at line 258 of file RTABMapApp.cpp.
void RTABMapApp::setSmoothing | ( | bool | enabled | ) |
Definition at line 2129 of file RTABMapApp.cpp.
void RTABMapApp::setTrajectoryMode | ( | bool | enabled | ) |
Definition at line 2062 of file RTABMapApp.cpp.
void RTABMapApp::SetViewPort | ( | int | width, |
int | height | ||
) |
Definition at line 940 of file RTABMapApp.cpp.
void RTABMapApp::setWireframe | ( | bool | enabled | ) |
Definition at line 2052 of file RTABMapApp.cpp.
|
private |
Definition at line 972 of file RTABMapApp.cpp.
bool RTABMapApp::startCamera | ( | JNIEnv * | env, |
jobject | iBinder, | ||
jobject | context, | ||
jobject | activity, | ||
int | driver | ||
) |
Definition at line 659 of file RTABMapApp.cpp.
void RTABMapApp::stopCamera | ( | ) |
Definition at line 805 of file RTABMapApp.cpp.
bool RTABMapApp::writeExportedMesh | ( | const std::string & | directory, |
const std::string & | name | ||
) |
Definition at line 3164 of file RTABMapApp.cpp.
|
private |
Definition at line 190 of file RTABMapApp.h.
|
private |
Definition at line 199 of file RTABMapApp.h.
|
private |
Definition at line 210 of file RTABMapApp.h.
|
private |
Definition at line 220 of file RTABMapApp.h.
|
private |
Definition at line 175 of file RTABMapApp.h.
|
private |
Definition at line 188 of file RTABMapApp.h.
|
private |
Definition at line 174 of file RTABMapApp.h.
|
private |
Definition at line 212 of file RTABMapApp.h.
|
private |
Definition at line 239 of file RTABMapApp.h.
|
private |
Definition at line 204 of file RTABMapApp.h.
|
private |
Definition at line 193 of file RTABMapApp.h.
|
private |
Definition at line 196 of file RTABMapApp.h.
|
private |
Definition at line 248 of file RTABMapApp.h.
|
private |
Definition at line 203 of file RTABMapApp.h.
|
private |
Definition at line 187 of file RTABMapApp.h.
|
private |
Definition at line 223 of file RTABMapApp.h.
|
private |
Definition at line 206 of file RTABMapApp.h.
|
private |
Definition at line 208 of file RTABMapApp.h.
|
private |
Definition at line 189 of file RTABMapApp.h.
|
private |
Definition at line 209 of file RTABMapApp.h.
|
private |
Definition at line 181 of file RTABMapApp.h.
|
private |
Definition at line 216 of file RTABMapApp.h.
|
private |
Definition at line 219 of file RTABMapApp.h.
|
private |
Definition at line 218 of file RTABMapApp.h.
|
private |
Definition at line 183 of file RTABMapApp.h.
|
private |
Definition at line 178 of file RTABMapApp.h.
|
private |
Definition at line 231 of file RTABMapApp.h.
|
private |
Definition at line 201 of file RTABMapApp.h.
|
private |
Definition at line 237 of file RTABMapApp.h.
|
private |
Definition at line 191 of file RTABMapApp.h.
|
private |
Definition at line 197 of file RTABMapApp.h.
|
private |
Definition at line 195 of file RTABMapApp.h.
|
private |
Definition at line 213 of file RTABMapApp.h.
|
private |
Definition at line 241 of file RTABMapApp.h.
|
private |
Definition at line 194 of file RTABMapApp.h.
|
private |
Definition at line 192 of file RTABMapApp.h.
|
private |
Definition at line 182 of file RTABMapApp.h.
|
private |
Definition at line 180 of file RTABMapApp.h.
|
private |
Definition at line 234 of file RTABMapApp.h.
|
private |
Definition at line 242 of file RTABMapApp.h.
|
private |
Definition at line 205 of file RTABMapApp.h.
|
private |
Definition at line 224 of file RTABMapApp.h.
|
private |
Definition at line 226 of file RTABMapApp.h.
|
private |
Definition at line 227 of file RTABMapApp.h.
|
private |
Definition at line 225 of file RTABMapApp.h.
|
private |
Definition at line 235 of file RTABMapApp.h.
|
private |
Definition at line 243 of file RTABMapApp.h.
|
private |
Definition at line 207 of file RTABMapApp.h.
|
private |
Definition at line 253 of file RTABMapApp.h.
|
private |
Definition at line 249 of file RTABMapApp.h.
|
private |
Definition at line 185 of file RTABMapApp.h.
|
private |
Definition at line 244 of file RTABMapApp.h.
|
private |
Definition at line 198 of file RTABMapApp.h.
|
private |
Definition at line 217 of file RTABMapApp.h.
|
private |
Definition at line 177 of file RTABMapApp.h.
|
private |
Definition at line 233 of file RTABMapApp.h.
|
private |
Definition at line 240 of file RTABMapApp.h.
|
private |
Definition at line 176 of file RTABMapApp.h.
|
private |
Definition at line 246 of file RTABMapApp.h.
|
private |
Definition at line 186 of file RTABMapApp.h.
|
private |
Definition at line 251 of file RTABMapApp.h.
|
private |
Definition at line 211 of file RTABMapApp.h.
|
private |
Definition at line 214 of file RTABMapApp.h.
|
private |
Definition at line 215 of file RTABMapApp.h.
|
private |
Definition at line 184 of file RTABMapApp.h.
|
private |
Definition at line 222 of file RTABMapApp.h.