Public Slots | Signals | Public Member Functions | Protected Member Functions | Private Member Functions | Private Attributes
rtabmap::CloudViewer Class Reference

#include <CloudViewer.h>

List of all members.

Public Slots

virtual void clear ()
void setBackgroundColor (const QColor &color)
void setCloudColorIndex (const std::string &id, int index)
void setCloudOpacity (const std::string &id, double opacity=1.0)
void setCloudPointSize (const std::string &id, int size)
void setCloudVisibility (const std::string &id, bool isVisible)
void setDefaultBackgroundColor (const QColor &color)

Signals

void configChanged ()

Public Member Functions

bool addCloud (const std::string &id, const pcl::PCLPointCloud2Ptr &binaryCloud, const Transform &pose, bool rgb, bool hasNormals, bool hasIntensity, const QColor &color=QColor())
bool addCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor())
bool addCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor())
bool addCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor())
bool addCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor())
bool addCloud (const std::string &id, const pcl::PointCloud< pcl::PointNormal >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor())
bool addCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor())
bool addCloudMesh (const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const std::vector< pcl::Vertices > &polygons, const Transform &pose=Transform::getIdentity())
bool addCloudMesh (const std::string &id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const std::vector< pcl::Vertices > &polygons, const Transform &pose=Transform::getIdentity())
bool addCloudMesh (const std::string &id, const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &cloud, const std::vector< pcl::Vertices > &polygons, const Transform &pose=Transform::getIdentity())
bool addCloudMesh (const std::string &id, const pcl::PolygonMesh::Ptr &mesh, const Transform &pose=Transform::getIdentity())
bool addCloudTextureMesh (const std::string &id, const pcl::TextureMesh::Ptr &textureMesh, const cv::Mat &texture, const Transform &pose=Transform::getIdentity())
bool addOccupancyGridMap (const cv::Mat &map8U, float resolution, float xMin, float yMin, float opacity)
bool addOctomap (const OctoMap *octomap, unsigned int treeDepth=0, bool volumeRepresentation=true)
void addOrUpdateCoordinate (const std::string &id, const Transform &transform, double scale, bool foreground=false)
void addOrUpdateCube (const std::string &id, const Transform &pose, float width, float height, float depth, const QColor &color, bool wireframe=false, bool foreground=false)
void addOrUpdateFrustum (const std::string &id, const Transform &transform, const Transform &localTransform, double scale, const QColor &color=QColor())
void addOrUpdateGraph (const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &graph, const QColor &color=Qt::gray)
void addOrUpdateLine (const std::string &id, const Transform &from, const Transform &to, const QColor &color, bool arrow=false, bool foreground=false)
void addOrUpdateQuad (const std::string &id, const Transform &pose, float width, float height, const QColor &color, bool foreground=false)
void addOrUpdateQuad (const std::string &id, const Transform &pose, float widthLeft, float widthRight, float heightBottom, float heightTop, const QColor &color, bool foreground=false)
void addOrUpdateSphere (const std::string &id, const Transform &pose, float radius, const QColor &color, bool foreground=false)
void addOrUpdateText (const std::string &id, const std::string &text, const Transform &position, double scale, const QColor &color, bool foreground=true)
bool addTextureMesh (const pcl::TextureMesh &mesh, const cv::Mat &texture, const std::string &id="texture", int viewport=0)
void buildPickingLocator (bool enable)
void clearTrajectory ()
 CloudViewer (QWidget *parent=0, CloudViewerInteractorStyle *style=CloudViewerInteractorStyle::New())
const QMap< std::string,
Transform > & 
getAddedClouds () const
const std::set< std::string > & getAddedCoordinates () const
const std::set< std::string > & getAddedCubes () const
const QMap< std::string,
Transform > & 
getAddedFrustums () const
const std::set< std::string > & getAddedLines () const
const std::set< std::string > & getAddedQuads () const
const std::set< std::string > & getAddedSpheres () const
const std::set< std::string > & getAddedTexts () const
const QColor & getBackgroundColor () const
void getCameraPosition (float &x, float &y, float &z, float &focalX, float &focalY, float &focalZ, float &upX, float &upY, float &upZ) const
bool getCloudVisibility (const std::string &id)
QColor getColor (const std::string &id)
const QColor & getDefaultBackgroundColor () const
QColor getFrustumColor () const
float getFrustumScale () const
unsigned int getGridCellCount () const
float getGridCellSize () const
std::string getIdByActor (vtkProp *actor) const
const std::map< std::string,
vtkSmartPointer< vtkOBBTree > > & 
getLocators () const
float getNormalsScale () const
int getNormalsStep () const
bool getPose (const std::string &id, Transform &pose)
double getRenderingRate () const
Transform getTargetPose () const
unsigned int getTrajectorySize () const
bool isCameraFree () const
bool isCameraLockZ () const
bool isCameraOrtho () const
bool isCameraTargetFollow () const
bool isCameraTargetLocked () const
bool isFrustumShown () const
bool isGridShown () const
bool isNormalsShown () const
bool isTrajectoryShown () const
void loadSettings (QSettings &settings, const QString &group="")
void removeAllClouds ()
void removeAllCoordinates ()
void removeAllCubes ()
void removeAllFrustums (bool exceptCameraReference=false)
void removeAllGraphs ()
void removeAllLines ()
void removeAllQuads ()
void removeAllSpheres ()
void removeAllTexts ()
bool removeCloud (const std::string &id)
void removeCoordinate (const std::string &id)
void removeCube (const std::string &id)
void removeFrustum (const std::string &id)
void removeGraph (const std::string &id)
void removeLine (const std::string &id)
void removeOccupancyGridMap ()
void removeOctomap ()
void removeQuad (const std::string &id)
void removeSphere (const std::string &id)
void removeText (const std::string &id)
void resetCamera ()
void saveSettings (QSettings &settings, const QString &group="") const
void setBackfaceCulling (bool enabled, bool frontfaceCulling)
void setCameraFree ()
void setCameraLockZ (bool enabled=true)
void setCameraOrtho (bool enabled=true)
void setCameraPosition (float x, float y, float z, float focalX, float focalY, float focalZ, float upX, float upY, float upZ)
void setCameraTargetFollow (bool enabled=true)
void setCameraTargetLocked (bool enabled=true)
void setColor (const std::string &id, const QColor &color)
void setEdgeVisibility (bool visible)
void setFrustumColor (QColor value)
void setFrustumScale (float value)
void setFrustumShown (bool shown)
void setGridCellCount (unsigned int count)
void setGridCellSize (float size)
void setGridShown (bool shown)
void setInteractorLayer (int layer)
void setLighting (bool on)
void setNormalsScale (float scale)
void setNormalsShown (bool shown)
void setNormalsStep (int step)
void setPolygonPicking (bool enabled)
void setRenderingRate (double rate)
void setShading (bool on)
void setTrajectoryShown (bool shown)
void setTrajectorySize (unsigned int value)
void updateCameraFrustum (const Transform &pose, const StereoCameraModel &model)
void updateCameraFrustum (const Transform &pose, const CameraModel &model)
void updateCameraFrustums (const Transform &pose, const std::vector< CameraModel > &models)
void updateCameraTargetPosition (const Transform &pose)
bool updateCloudPose (const std::string &id, const Transform &pose)
bool updateCoordinatePose (const std::string &id, const Transform &transform)
bool updateFrustumPose (const std::string &id, const Transform &pose)
virtual ~CloudViewer ()

Protected Member Functions

virtual void contextMenuEvent (QContextMenuEvent *event)
virtual void handleAction (QAction *event)
virtual void keyPressEvent (QKeyEvent *event)
virtual void keyReleaseEvent (QKeyEvent *event)
QMenu * menu ()
virtual void mouseMoveEvent (QMouseEvent *event)
virtual void mousePressEvent (QMouseEvent *event)
pcl::visualization::PCLVisualizer * visualizer ()
virtual void wheelEvent (QWheelEvent *event)

Private Member Functions

void addGrid ()
void createMenu ()
void removeGrid ()

Private Attributes

QAction * _aBackfaceCulling
QAction * _aCameraOrtho
QAction * _aClearTrajectory
QMap< std::string, Transform_addedClouds
QAction * _aFollowCamera
QAction * _aLockCamera
QAction * _aLockViewZ
QAction * _aPolygonPicking
QAction * _aResetCamera
QAction * _aSetBackgroundColor
QAction * _aSetEdgeVisibility
QAction * _aSetFlatShading
QAction * _aSetFrustumColor
QAction * _aSetFrustumScale
QAction * _aSetGridCellCount
QAction * _aSetGridCellSize
QAction * _aSetLighting
QAction * _aSetNormalsScale
QAction * _aSetNormalsStep
QAction * _aSetRenderingRate
QAction * _aSetTrajectorySize
QAction * _aShowFrustum
QAction * _aShowGrid
QAction * _aShowNormals
QAction * _aShowTrajectory
bool _buildLocator
std::set< std::string > _coordinates
std::set< std::string > _cubes
QColor _currentBgColor
QColor _defaultBgColor
bool _frontfaceCulling
QColor _frustumColor
QMap< std::string, Transform_frustums
float _frustumScale
std::set< std::string > _graphes
unsigned int _gridCellCount
float _gridCellSize
std::list< std::string > _gridLines
QSet< Qt::Key > _keysPressed
cv::Vec3d _lastCameraOrientation
cv::Vec3d _lastCameraPose
Transform _lastPose
std::set< std::string > _lines
std::map< std::string,
vtkSmartPointer< vtkOBBTree > > 
_locators
unsigned int _maxTrajectorySize
QMenu * _menu
float _normalsScale
int _normalsStep
vtkProp * _octomapActor
std::set< std::string > _quads
double _renderingRate
std::set< std::string > _spheres
std::set< std::string > _texts
pcl::PointCloud< pcl::PointXYZ >
::Ptr 
_trajectory
pcl::visualization::PCLVisualizer * _visualizer

Detailed Description

Definition at line 69 of file CloudViewer.h.


Constructor & Destructor Documentation

Definition at line 82 of file CloudViewer.cpp.

Definition at line 186 of file CloudViewer.cpp.


Member Function Documentation

bool rtabmap::CloudViewer::addCloud ( const std::string &  id,
const pcl::PCLPointCloud2Ptr &  binaryCloud,
const Transform pose,
bool  rgb,
bool  hasNormals,
bool  hasIntensity,
const QColor &  color = QColor() 
)

Definition at line 455 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloud ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &  cloud,
const Transform pose = Transform::getIdentity(),
const QColor &  color = QColor() 
)

Definition at line 566 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloud ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
const Transform pose = Transform::getIdentity(),
const QColor &  color = QColor() 
)

Definition at line 577 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloud ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZINormal >::Ptr &  cloud,
const Transform pose = Transform::getIdentity(),
const QColor &  color = QColor() 
)

Definition at line 588 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloud ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZI >::Ptr &  cloud,
const Transform pose = Transform::getIdentity(),
const QColor &  color = QColor() 
)

Definition at line 599 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloud ( const std::string &  id,
const pcl::PointCloud< pcl::PointNormal >::Ptr &  cloud,
const Transform pose = Transform::getIdentity(),
const QColor &  color = QColor() 
)

Definition at line 610 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloud ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  cloud,
const Transform pose = Transform::getIdentity(),
const QColor &  color = QColor() 
)

Definition at line 621 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloudMesh ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  cloud,
const std::vector< pcl::Vertices > &  polygons,
const Transform pose = Transform::getIdentity() 
)

Definition at line 632 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloudMesh ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &  cloud,
const std::vector< pcl::Vertices > &  polygons,
const Transform pose = Transform::getIdentity() 
)

Definition at line 666 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloudMesh ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZRGBNormal >::Ptr &  cloud,
const std::vector< pcl::Vertices > &  polygons,
const Transform pose = Transform::getIdentity() 
)

Definition at line 700 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloudMesh ( const std::string &  id,
const pcl::PolygonMesh::Ptr &  mesh,
const Transform pose = Transform::getIdentity() 
)

Definition at line 734 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addCloudTextureMesh ( const std::string &  id,
const pcl::TextureMesh::Ptr &  textureMesh,
const cv::Mat &  texture,
const Transform pose = Transform::getIdentity() 
)

Definition at line 767 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addGrid ( ) [private]

Definition at line 2715 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addOccupancyGridMap ( const cv::Mat &  map8U,
float  resolution,
float  xMin,
float  yMin,
float  opacity 
)

Definition at line 1203 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addOctomap ( const OctoMap octomap,
unsigned int  treeDepth = 0,
bool  volumeRepresentation = true 
)

Definition at line 805 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateCoordinate ( const std::string &  id,
const Transform transform,
double  scale,
bool  foreground = false 
)

Definition at line 1269 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateCube ( const std::string &  id,
const Transform pose,
float  width,
float  height,
float  depth,
const QColor &  color,
bool  wireframe = false,
bool  foreground = false 
)

Definition at line 1463 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateFrustum ( const std::string &  id,
const Transform transform,
const Transform localTransform,
double  scale,
const QColor &  color = QColor() 
)

Definition at line 1677 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateGraph ( const std::string &  id,
const pcl::PointCloud< pcl::PointXYZ >::Ptr &  graph,
const QColor &  color = Qt::gray 
)

Definition at line 1825 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateLine ( const std::string &  id,
const Transform from,
const Transform to,
const QColor &  color,
bool  arrow = false,
bool  foreground = false 
)

Definition at line 1341 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateQuad ( const std::string &  id,
const Transform pose,
float  width,
float  height,
const QColor &  color,
bool  foreground = false 
)

Definition at line 1525 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateQuad ( const std::string &  id,
const Transform pose,
float  widthLeft,
float  widthRight,
float  heightBottom,
float  heightTop,
const QColor &  color,
bool  foreground = false 
)

Definition at line 1536 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateSphere ( const std::string &  id,
const Transform pose,
float  radius,
const QColor &  color,
bool  foreground = false 
)

Definition at line 1407 of file CloudViewer.cpp.

void rtabmap::CloudViewer::addOrUpdateText ( const std::string &  id,
const std::string &  text,
const Transform position,
double  scale,
const QColor &  color,
bool  foreground = true 
)

Definition at line 1886 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::addTextureMesh ( const pcl::TextureMesh &  mesh,
const cv::Mat &  texture,
const std::string &  id = "texture",
int  viewport = 0 
)

Definition at line 1030 of file CloudViewer.cpp.

Definition at line 2802 of file CloudViewer.cpp.

void rtabmap::CloudViewer::clear ( ) [virtual, slot]

Definition at line 194 of file CloudViewer.cpp.

Definition at line 1962 of file CloudViewer.cpp.

void rtabmap::CloudViewer::contextMenuEvent ( QContextMenuEvent *  event) [protected, virtual]

Definition at line 3033 of file CloudViewer.cpp.

Definition at line 214 of file CloudViewer.cpp.

const QMap<std::string, Transform>& rtabmap::CloudViewer::getAddedClouds ( ) const [inline]

Definition at line 307 of file CloudViewer.h.

const std::set<std::string>& rtabmap::CloudViewer::getAddedCoordinates ( ) const [inline]

Definition at line 201 of file CloudViewer.h.

const std::set<std::string>& rtabmap::CloudViewer::getAddedCubes ( ) const [inline]

Definition at line 235 of file CloudViewer.h.

const QMap<std::string, Transform>& rtabmap::CloudViewer::getAddedFrustums ( ) const [inline]

Definition at line 268 of file CloudViewer.h.

const std::set<std::string>& rtabmap::CloudViewer::getAddedLines ( ) const [inline]

Definition at line 212 of file CloudViewer.h.

const std::set<std::string>& rtabmap::CloudViewer::getAddedQuads ( ) const [inline]

Definition at line 255 of file CloudViewer.h.

const std::set<std::string>& rtabmap::CloudViewer::getAddedSpheres ( ) const [inline]

Definition at line 222 of file CloudViewer.h.

const std::set<std::string>& rtabmap::CloudViewer::getAddedTexts ( ) const [inline]

Definition at line 286 of file CloudViewer.h.

const QColor & rtabmap::CloudViewer::getBackgroundColor ( ) const

Definition at line 2528 of file CloudViewer.cpp.

void rtabmap::CloudViewer::getCameraPosition ( float &  x,
float &  y,
float &  z,
float &  focalX,
float &  focalY,
float &  focalZ,
float &  upX,
float &  upY,
float &  upZ 
) const

Definition at line 2313 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::getCloudVisibility ( const std::string &  id)

Definition at line 2559 of file CloudViewer.cpp.

QColor rtabmap::CloudViewer::getColor ( const std::string &  id)

Definition at line 2142 of file CloudViewer.cpp.

Definition at line 2514 of file CloudViewer.cpp.

Definition at line 1979 of file CloudViewer.cpp.

Definition at line 1974 of file CloudViewer.cpp.

Definition at line 2675 of file CloudViewer.cpp.

Definition at line 2679 of file CloudViewer.cpp.

std::string rtabmap::CloudViewer::getIdByActor ( vtkProp *  actor) const

Definition at line 2111 of file CloudViewer.cpp.

const std::map<std::string, vtkSmartPointer<vtkOBBTree> >& rtabmap::CloudViewer::getLocators ( ) const [inline]

Definition at line 356 of file CloudViewer.h.

Definition at line 2775 of file CloudViewer.cpp.

Definition at line 2771 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::getPose ( const std::string &  id,
Transform pose 
)

Definition at line 2092 of file CloudViewer.cpp.

Definition at line 2654 of file CloudViewer.cpp.

Definition at line 2102 of file CloudViewer.cpp.

Definition at line 1947 of file CloudViewer.cpp.

void rtabmap::CloudViewer::handleAction ( QAction *  event) [protected, virtual]

Definition at line 3043 of file CloudViewer.cpp.

Definition at line 2642 of file CloudViewer.cpp.

Definition at line 2646 of file CloudViewer.cpp.

Definition at line 2650 of file CloudViewer.cpp.

Definition at line 2638 of file CloudViewer.cpp.

Definition at line 2634 of file CloudViewer.cpp.

Definition at line 1969 of file CloudViewer.cpp.

Definition at line 2671 of file CloudViewer.cpp.

Definition at line 2767 of file CloudViewer.cpp.

Definition at line 1942 of file CloudViewer.cpp.

void rtabmap::CloudViewer::keyPressEvent ( QKeyEvent *  event) [protected, virtual]

Definition at line 2856 of file CloudViewer.cpp.

void rtabmap::CloudViewer::keyReleaseEvent ( QKeyEvent *  event) [protected, virtual]

Definition at line 2842 of file CloudViewer.cpp.

void rtabmap::CloudViewer::loadSettings ( QSettings &  settings,
const QString &  group = "" 
)

Definition at line 376 of file CloudViewer.cpp.

QMenu* rtabmap::CloudViewer::menu ( ) [inline, protected]

Definition at line 378 of file CloudViewer.h.

void rtabmap::CloudViewer::mouseMoveEvent ( QMouseEvent *  event) [protected, virtual]

Definition at line 2968 of file CloudViewer.cpp.

void rtabmap::CloudViewer::mousePressEvent ( QMouseEvent *  event) [protected, virtual]

Definition at line 2956 of file CloudViewer.cpp.

Definition at line 2074 of file CloudViewer.cpp.

Definition at line 1331 of file CloudViewer.cpp.

Definition at line 1515 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeAllFrustums ( bool  exceptCameraReference = false)

Definition at line 1812 of file CloudViewer.cpp.

Definition at line 1876 of file CloudViewer.cpp.

Definition at line 1397 of file CloudViewer.cpp.

Definition at line 1657 of file CloudViewer.cpp.

Definition at line 1453 of file CloudViewer.cpp.

Definition at line 1932 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::removeCloud ( const std::string &  id)

Definition at line 2082 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeCoordinate ( const std::string &  id)

Definition at line 1311 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeCube ( const std::string &  id)

Definition at line 1500 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeFrustum ( const std::string &  id)

Definition at line 1797 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeGraph ( const std::string &  id)

Definition at line 1860 of file CloudViewer.cpp.

Definition at line 2745 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeLine ( const std::string &  id)

Definition at line 1382 of file CloudViewer.cpp.

Definition at line 1261 of file CloudViewer.cpp.

Definition at line 1013 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeQuad ( const std::string &  id)

Definition at line 1642 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeSphere ( const std::string &  id)

Definition at line 1438 of file CloudViewer.cpp.

void rtabmap::CloudViewer::removeText ( const std::string &  id)

Definition at line 1917 of file CloudViewer.cpp.

Definition at line 2028 of file CloudViewer.cpp.

void rtabmap::CloudViewer::saveSettings ( QSettings &  settings,
const QString &  group = "" 
) const

Definition at line 317 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setBackfaceCulling ( bool  enabled,
bool  frontfaceCulling 
)

Definition at line 2220 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setBackgroundColor ( const QColor &  color) [slot]

Definition at line 2533 of file CloudViewer.cpp.

Definition at line 2612 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setCameraLockZ ( bool  enabled = true)

Definition at line 2618 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setCameraOrtho ( bool  enabled = true)

Definition at line 2623 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setCameraPosition ( float  x,
float  y,
float  z,
float  focalX,
float  focalY,
float  focalZ,
float  upX,
float  upY,
float  upZ 
)

Definition at line 2338 of file CloudViewer.cpp.

Definition at line 2607 of file CloudViewer.cpp.

Definition at line 2602 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setCloudColorIndex ( const std::string &  id,
int  index 
) [slot]

Definition at line 2574 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setCloudOpacity ( const std::string &  id,
double  opacity = 1.0 
) [slot]

Definition at line 2582 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setCloudPointSize ( const std::string &  id,
int  size 
) [slot]

Definition at line 2592 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setCloudVisibility ( const std::string &  id,
bool  isVisible 
) [slot]

Definition at line 2539 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setColor ( const std::string &  id,
const QColor &  color 
)

Definition at line 2184 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setDefaultBackgroundColor ( const QColor &  color) [slot]

Definition at line 2519 of file CloudViewer.cpp.

Definition at line 2284 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setFrustumColor ( QColor  value)

Definition at line 2014 of file CloudViewer.cpp.

Definition at line 2009 of file CloudViewer.cpp.

Definition at line 1984 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setGridCellCount ( unsigned int  count)

Definition at line 2683 of file CloudViewer.cpp.

Definition at line 2699 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setGridShown ( bool  shown)

Definition at line 2659 of file CloudViewer.cpp.

Definition at line 2295 of file CloudViewer.cpp.

Definition at line 2262 of file CloudViewer.cpp.

Definition at line 2790 of file CloudViewer.cpp.

Definition at line 2754 of file CloudViewer.cpp.

Definition at line 2779 of file CloudViewer.cpp.

Definition at line 2234 of file CloudViewer.cpp.

Definition at line 2256 of file CloudViewer.cpp.

Definition at line 2273 of file CloudViewer.cpp.

Definition at line 1952 of file CloudViewer.cpp.

void rtabmap::CloudViewer::setTrajectorySize ( unsigned int  value)

Definition at line 1957 of file CloudViewer.cpp.

void rtabmap::CloudViewer::updateCameraFrustum ( const Transform pose,
const StereoCameraModel model 
)

Definition at line 2468 of file CloudViewer.cpp.

void rtabmap::CloudViewer::updateCameraFrustum ( const Transform pose,
const CameraModel model 
)

Definition at line 2481 of file CloudViewer.cpp.

void rtabmap::CloudViewer::updateCameraFrustums ( const Transform pose,
const std::vector< CameraModel > &  models 
)

Definition at line 2488 of file CloudViewer.cpp.

Definition at line 2347 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::updateCloudPose ( const std::string &  id,
const Transform pose 
)

Definition at line 427 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::updateCoordinatePose ( const std::string &  id,
const Transform transform 
)

Definition at line 1295 of file CloudViewer.cpp.

bool rtabmap::CloudViewer::updateFrustumPose ( const std::string &  id,
const Transform pose 
)

Definition at line 1754 of file CloudViewer.cpp.

pcl::visualization::PCLVisualizer* rtabmap::CloudViewer::visualizer ( ) [inline, protected]

Definition at line 379 of file CloudViewer.h.

void rtabmap::CloudViewer::wheelEvent ( QWheelEvent *  event) [protected, virtual]

Definition at line 3021 of file CloudViewer.cpp.


Member Data Documentation

Definition at line 410 of file CloudViewer.h.

Definition at line 392 of file CloudViewer.h.

Definition at line 395 of file CloudViewer.h.

QMap<std::string, Transform> rtabmap::CloudViewer::_addedClouds [private]

Definition at line 433 of file CloudViewer.h.

Definition at line 389 of file CloudViewer.h.

Definition at line 388 of file CloudViewer.h.

Definition at line 391 of file CloudViewer.h.

Definition at line 411 of file CloudViewer.h.

Definition at line 390 of file CloudViewer.h.

Definition at line 405 of file CloudViewer.h.

Definition at line 409 of file CloudViewer.h.

Definition at line 408 of file CloudViewer.h.

Definition at line 398 of file CloudViewer.h.

Definition at line 397 of file CloudViewer.h.

Definition at line 400 of file CloudViewer.h.

Definition at line 401 of file CloudViewer.h.

Definition at line 407 of file CloudViewer.h.

Definition at line 404 of file CloudViewer.h.

Definition at line 403 of file CloudViewer.h.

Definition at line 406 of file CloudViewer.h.

Definition at line 394 of file CloudViewer.h.

Definition at line 396 of file CloudViewer.h.

Definition at line 399 of file CloudViewer.h.

Definition at line 402 of file CloudViewer.h.

Definition at line 393 of file CloudViewer.h.

Definition at line 429 of file CloudViewer.h.

std::set<std::string> rtabmap::CloudViewer::_coordinates [private]

Definition at line 414 of file CloudViewer.h.

std::set<std::string> rtabmap::CloudViewer::_cubes [private]

Definition at line 418 of file CloudViewer.h.

Definition at line 438 of file CloudViewer.h.

Definition at line 437 of file CloudViewer.h.

Definition at line 439 of file CloudViewer.h.

Definition at line 424 of file CloudViewer.h.

QMap<std::string, Transform> rtabmap::CloudViewer::_frustums [private]

Definition at line 420 of file CloudViewer.h.

Definition at line 423 of file CloudViewer.h.

std::set<std::string> rtabmap::CloudViewer::_graphes [private]

Definition at line 413 of file CloudViewer.h.

unsigned int rtabmap::CloudViewer::_gridCellCount [private]

Definition at line 425 of file CloudViewer.h.

Definition at line 426 of file CloudViewer.h.

std::list<std::string> rtabmap::CloudViewer::_gridLines [private]

Definition at line 435 of file CloudViewer.h.

QSet<Qt::Key> rtabmap::CloudViewer::_keysPressed [private]

Definition at line 436 of file CloudViewer.h.

Definition at line 431 of file CloudViewer.h.

Definition at line 432 of file CloudViewer.h.

Definition at line 434 of file CloudViewer.h.

std::set<std::string> rtabmap::CloudViewer::_lines [private]

Definition at line 416 of file CloudViewer.h.

std::map<std::string, vtkSmartPointer<vtkOBBTree> > rtabmap::CloudViewer::_locators [private]

Definition at line 430 of file CloudViewer.h.

Definition at line 422 of file CloudViewer.h.

QMenu* rtabmap::CloudViewer::_menu [private]

Definition at line 412 of file CloudViewer.h.

Definition at line 428 of file CloudViewer.h.

Definition at line 427 of file CloudViewer.h.

Definition at line 441 of file CloudViewer.h.

std::set<std::string> rtabmap::CloudViewer::_quads [private]

Definition at line 419 of file CloudViewer.h.

Definition at line 440 of file CloudViewer.h.

std::set<std::string> rtabmap::CloudViewer::_spheres [private]

Definition at line 417 of file CloudViewer.h.

std::set<std::string> rtabmap::CloudViewer::_texts [private]

Definition at line 415 of file CloudViewer.h.

pcl::PointCloud<pcl::PointXYZ>::Ptr rtabmap::CloudViewer::_trajectory [private]

Definition at line 421 of file CloudViewer.h.

pcl::visualization::PCLVisualizer* rtabmap::CloudViewer::_visualizer [private]

Definition at line 387 of file CloudViewer.h.


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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jun 6 2019 21:59:41