Classes | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
RTABMapApp Class Reference

#include <RTABMapApp.h>

Inheritance diagram for RTABMapApp:
Inheritance graph
[legend]

List of all members.

Classes

struct  Mesh

Public Member Functions

bool exportMesh (const std::string &filePath)
void InitializeGLContent ()
void onCreate (JNIEnv *env, jobject caller_activity)
void onPause ()
void onPointCloudAvailable (const TangoXYZij *xyz_ij)
void onPoseAvailable (const TangoPoseData *pose)
void onTangoEventAvailable (const TangoEvent *event)
bool onTangoServiceConnected (JNIEnv *env, jobject iBinder)
void OnTouchEvent (int touch_count, tango_gl::GestureCamera::TouchEvent event, float x0, float y0, float x1, float y1)
void openDatabase (const std::string &databasePath)
int postProcessing (int approach)
int Render ()
void resetMapping ()
 RTABMapApp ()
void save ()
void setAutoExposure (bool enabled)
void SetCameraType (tango_gl::GestureCamera::CameraType camera_type)
void setFullResolution (bool enabled)
void setGraphOptimization (bool enabled)
void setGraphVisible (bool visible)
void setLocalizationMode (bool enabled)
void setMapCloudShown (bool shown)
int setMappingParameter (const std::string &key, const std::string &value)
void setMaxCloudDepth (float value)
void setMeshAngleTolerance (float value)
void setMeshRendering (bool enabled)
void setMeshTriangleSize (int value)
void setNodesFiltering (bool enabled)
void setOdomCloudShown (bool shown)
void setPausedMapping (bool paused)
void setTrajectoryMode (bool enabled)
void SetViewPort (int width, int height)
void TangoResetMotionTracking ()
 ~RTABMapApp ()

Protected Member Functions

virtual void handleEvent (UEvent *event)

Private Member Functions

rtabmap::ParametersMap getRtabmapParameters ()

Private Attributes

bool autoExposure_
rtabmap::CameraTangocamera_
bool clearSceneOnNextRender_
std::map< int, MeshcreatedMeshes_
bool fullResolution_
bool graphOptimization_
int lastDrawnCloudsCount_
bool localizationMode_
LogHandlerlogHandler_
Scene main_scene_
rtabmap::ParametersMap mappingParameters_
float maxCloudDepth_
float meshAngleToleranceDeg_
boost::mutex meshesMutex_
int meshTrianglePix_
bool nodesFiltering_
bool odomCloudShown_
std::list< rtabmap::OdometryEventodomEvents_
boost::mutex odomMutex_
std::list< rtabmap::TransformposeEvents_
boost::mutex poseMutex_
std::map< int, rtabmap::TransformrawPoses_
float renderingFPS_
rtabmap::Rtabmaprtabmap_
std::list< rtabmap::StatisticsrtabmapEvents_
boost::mutex rtabmapMutex_
rtabmap::RtabmapThreadrtabmapThread_
std::pair
< rtabmap::RtabmapEventInit::Status,
std::string > 
status_
int totalPoints_
int totalPolygons_
bool trajectoryMode_

Detailed Description

Definition at line 47 of file RTABMapApp.h.


Constructor & Destructor Documentation

Definition at line 90 of file RTABMapApp.cpp.

Definition at line 115 of file RTABMapApp.cpp.


Member Function Documentation

bool RTABMapApp::exportMesh ( const std::string &  filePath)

Definition at line 725 of file RTABMapApp.cpp.

Definition at line 63 of file RTABMapApp.cpp.

void RTABMapApp::handleEvent ( UEvent event) [protected, virtual]

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 but must not be deleted.

Implements UEventsHandler.

Definition at line 970 of file RTABMapApp.cpp.

Definition at line 260 of file RTABMapApp.cpp.

void RTABMapApp::onCreate ( JNIEnv *  env,
jobject  caller_activity 
)

Definition at line 131 of file RTABMapApp.cpp.

Definition at line 244 of file RTABMapApp.cpp.

void RTABMapApp::onPointCloudAvailable ( const TangoXYZij *  xyz_ij)
void RTABMapApp::onPoseAvailable ( const TangoPoseData *  pose)
void RTABMapApp::onTangoEventAvailable ( const TangoEvent *  event)
bool RTABMapApp::onTangoServiceConnected ( JNIEnv *  env,
jobject  iBinder 
)

Definition at line 221 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 571 of file RTABMapApp.cpp.

void RTABMapApp::openDatabase ( const std::string &  databasePath)

Definition at line 169 of file RTABMapApp.cpp.

int RTABMapApp::postProcessing ( int  approach)

Definition at line 906 of file RTABMapApp.cpp.

Definition at line 288 of file RTABMapApp.cpp.

Definition at line 709 of file RTABMapApp.cpp.

void RTABMapApp::save ( )

Definition at line 720 of file RTABMapApp.cpp.

void RTABMapApp::setAutoExposure ( bool  enabled)

Definition at line 651 of file RTABMapApp.cpp.

Definition at line 566 of file RTABMapApp.cpp.

void RTABMapApp::setFullResolution ( bool  enabled)

Definition at line 663 of file RTABMapApp.cpp.

void RTABMapApp::setGraphOptimization ( bool  enabled)

Definition at line 621 of file RTABMapApp.cpp.

void RTABMapApp::setGraphVisible ( bool  visible)

Definition at line 646 of file RTABMapApp.cpp.

void RTABMapApp::setLocalizationMode ( bool  enabled)

Definition at line 606 of file RTABMapApp.cpp.

void RTABMapApp::setMapCloudShown ( bool  shown)

Definition at line 593 of file RTABMapApp.cpp.

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

Definition at line 693 of file RTABMapApp.cpp.

void RTABMapApp::setMaxCloudDepth ( float  value)

Definition at line 678 of file RTABMapApp.cpp.

void RTABMapApp::setMeshAngleTolerance ( float  value)

Definition at line 683 of file RTABMapApp.cpp.

void RTABMapApp::setMeshRendering ( bool  enabled)

Definition at line 602 of file RTABMapApp.cpp.

void RTABMapApp::setMeshTriangleSize ( int  value)

Definition at line 688 of file RTABMapApp.cpp.

void RTABMapApp::setNodesFiltering ( bool  enabled)

Definition at line 641 of file RTABMapApp.cpp.

void RTABMapApp::setOdomCloudShown ( bool  shown)

Definition at line 597 of file RTABMapApp.cpp.

void RTABMapApp::setPausedMapping ( bool  paused)

Definition at line 577 of file RTABMapApp.cpp.

void RTABMapApp::setTrajectoryMode ( bool  enabled)

Definition at line 611 of file RTABMapApp.cpp.

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

Definition at line 267 of file RTABMapApp.cpp.

Definition at line 255 of file RTABMapApp.cpp.


Member Data Documentation

bool RTABMapApp::autoExposure_ [private]

Definition at line 150 of file RTABMapApp.h.

Definition at line 140 of file RTABMapApp.h.

Definition at line 159 of file RTABMapApp.h.

std::map<int, Mesh> RTABMapApp::createdMeshes_ [private]

Definition at line 186 of file RTABMapApp.h.

Definition at line 151 of file RTABMapApp.h.

Definition at line 146 of file RTABMapApp.h.

Definition at line 162 of file RTABMapApp.h.

Definition at line 148 of file RTABMapApp.h.

Definition at line 143 of file RTABMapApp.h.

Definition at line 167 of file RTABMapApp.h.

Definition at line 156 of file RTABMapApp.h.

float RTABMapApp::maxCloudDepth_ [private]

Definition at line 152 of file RTABMapApp.h.

Definition at line 154 of file RTABMapApp.h.

boost::mutex RTABMapApp::meshesMutex_ [private]

Definition at line 174 of file RTABMapApp.h.

Definition at line 153 of file RTABMapApp.h.

Definition at line 147 of file RTABMapApp.h.

Definition at line 145 of file RTABMapApp.h.

Definition at line 170 of file RTABMapApp.h.

boost::mutex RTABMapApp::odomMutex_ [private]

Definition at line 175 of file RTABMapApp.h.

Definition at line 171 of file RTABMapApp.h.

boost::mutex RTABMapApp::poseMutex_ [private]

Definition at line 176 of file RTABMapApp.h.

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

Definition at line 187 of file RTABMapApp.h.

float RTABMapApp::renderingFPS_ [private]

Definition at line 163 of file RTABMapApp.h.

Definition at line 142 of file RTABMapApp.h.

Definition at line 169 of file RTABMapApp.h.

boost::mutex RTABMapApp::rtabmapMutex_ [private]

Definition at line 173 of file RTABMapApp.h.

Definition at line 141 of file RTABMapApp.h.

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

Definition at line 189 of file RTABMapApp.h.

int RTABMapApp::totalPoints_ [private]

Definition at line 160 of file RTABMapApp.h.

Definition at line 161 of file RTABMapApp.h.

Definition at line 149 of file RTABMapApp.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:31