#include <CloudViewer.h>
Public Slots | |
virtual void | clear () |
void | setBackgroundColor (const QColor &color) |
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 haveNormals, 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::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 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 showEdges=true, bool lightingOn=false) |
void | addOrUpdateCoordinate (const std::string &id, const Transform &transform, double scale) |
void | addOrUpdateFrustum (const std::string &id, const Transform &transform, 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) |
void | addOrUpdateText (const std::string &id, const std::string &text, const Transform &position, double scale, const QColor &color) |
void | clearTrajectory () |
CloudViewer (QWidget *parent=0) | |
const QMap< std::string, Transform > & | getAddedClouds () 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) |
const QColor & | getDefaultBackgroundColor () const |
QColor | getFrustumColor () const |
float | getFrustumScale () const |
unsigned int | getGridCellCount () const |
float | getGridCellSize () 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 | isCameraTargetFollow () const |
bool | isCameraTargetLocked () const |
bool | isFrustumShown () const |
bool | isGridShown () const |
bool | isTrajectoryShown () const |
void | loadSettings (QSettings &settings, const QString &group="") |
void | removeAllClouds () |
void | removeAllCoordinates () |
void | removeAllFrustums () |
void | removeAllGraphs () |
void | removeAllLines () |
void | removeAllTexts () |
bool | removeCloud (const std::string &id) |
void | removeCoordinate (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 | 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 | 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 | 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 | setRenderingRate (double rate) |
void | setTrajectoryShown (bool shown) |
void | setTrajectorySize (unsigned int value) |
void | setWorkingDirectory (const QString &path) |
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) |
virtual void | wheelEvent (QWheelEvent *event) |
Private Member Functions | |
void | addGrid () |
void | createMenu () |
void | removeGrid () |
Private Attributes | |
QAction * | _aClearTrajectory |
QMap< std::string, Transform > | _addedClouds |
QAction * | _aFollowCamera |
QAction * | _aLockCamera |
QAction * | _aLockViewZ |
QAction * | _aResetCamera |
QAction * | _aSetBackgroundColor |
QAction * | _aSetFrustumColor |
QAction * | _aSetFrustumScale |
QAction * | _aSetGridCellCount |
QAction * | _aSetGridCellSize |
QAction * | _aSetRenderingRate |
QAction * | _aSetTrajectorySize |
QAction * | _aShowFrustum |
QAction * | _aShowGrid |
QAction * | _aShowTrajectory |
bool | _backfaceCulling |
std::set< std::string > | _coordinates |
QColor | _currentBgColor |
QColor | _defaultBgColor |
bool | _frontfaceCulling |
QColor | _frustumColor |
std::set< std::string > | _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 |
unsigned int | _maxTrajectorySize |
QMenu * | _menu |
vtkProp * | _octomapActor |
double | _renderingRate |
std::set< std::string > | _texts |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | _trajectory |
pcl::visualization::PCLVisualizer * | _visualizer |
QString | _workingDirectory |
Definition at line 67 of file CloudViewer.h.
rtabmap::CloudViewer::CloudViewer | ( | QWidget * | parent = 0 | ) |
Definition at line 105 of file CloudViewer.cpp.
rtabmap::CloudViewer::~CloudViewer | ( | ) | [virtual] |
Definition at line 174 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addCloud | ( | const std::string & | id, |
const pcl::PCLPointCloud2Ptr & | binaryCloud, | ||
const Transform & | pose, | ||
bool | rgb, | ||
bool | haveNormals, | ||
const QColor & | color = QColor() |
||
) |
Definition at line 383 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 467 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 478 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 489 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 500 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 511 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 541 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 571 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 601 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addCloudTextureMesh | ( | const std::string & | id, |
const pcl::TextureMesh::Ptr & | textureMesh, | ||
const Transform & | pose = Transform::getIdentity() |
||
) |
Definition at line 631 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addGrid | ( | ) | [private] |
Definition at line 1730 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addOccupancyGridMap | ( | const cv::Mat & | map8U, |
float | resolution, | ||
float | xMin, | ||
float | yMin, | ||
float | opacity | ||
) |
Definition at line 760 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addOctomap | ( | const OctoMap * | octomap, |
unsigned int | treeDepth = 0 , |
||
bool | showEdges = true , |
||
bool | lightingOn = false |
||
) |
Definition at line 655 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addOrUpdateCoordinate | ( | const std::string & | id, |
const Transform & | transform, | ||
double | scale | ||
) |
Definition at line 840 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addOrUpdateFrustum | ( | const std::string & | id, |
const Transform & | transform, | ||
double | scale, | ||
const QColor & | color = QColor() |
||
) |
Definition at line 985 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 1077 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addOrUpdateLine | ( | const std::string & | id, |
const Transform & | from, | ||
const Transform & | to, | ||
const QColor & | color, | ||
bool | arrow = false |
||
) |
Definition at line 911 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addOrUpdateText | ( | const std::string & | id, |
const std::string & | text, | ||
const Transform & | position, | ||
double | scale, | ||
const QColor & | color | ||
) |
Definition at line 1137 of file CloudViewer.cpp.
void rtabmap::CloudViewer::clear | ( | ) | [virtual, slot] |
Definition at line 182 of file CloudViewer.cpp.
Definition at line 1211 of file CloudViewer.cpp.
void rtabmap::CloudViewer::configChanged | ( | ) | [signal] |
void rtabmap::CloudViewer::contextMenuEvent | ( | QContextMenuEvent * | event | ) | [protected, virtual] |
Definition at line 1983 of file CloudViewer.cpp.
void rtabmap::CloudViewer::createMenu | ( | ) | [private] |
Definition at line 197 of file CloudViewer.cpp.
const QMap<std::string, Transform>& rtabmap::CloudViewer::getAddedClouds | ( | ) | const [inline] |
Definition at line 233 of file CloudViewer.h.
const QColor & rtabmap::CloudViewer::getBackgroundColor | ( | ) | const |
Definition at line 1570 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 1356 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::getCloudVisibility | ( | const std::string & | id | ) |
Definition at line 1595 of file CloudViewer.cpp.
const QColor & rtabmap::CloudViewer::getDefaultBackgroundColor | ( | ) | const |
Definition at line 1556 of file CloudViewer.cpp.
QColor rtabmap::CloudViewer::getFrustumColor | ( | ) | const |
Definition at line 1228 of file CloudViewer.cpp.
float rtabmap::CloudViewer::getFrustumScale | ( | ) | const |
Definition at line 1223 of file CloudViewer.cpp.
unsigned int rtabmap::CloudViewer::getGridCellCount | ( | ) | const |
Definition at line 1685 of file CloudViewer.cpp.
float rtabmap::CloudViewer::getGridCellSize | ( | ) | const |
Definition at line 1689 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::getPose | ( | const std::string & | id, |
Transform & | pose | ||
) |
Definition at line 1325 of file CloudViewer.cpp.
double rtabmap::CloudViewer::getRenderingRate | ( | ) | const |
Definition at line 1693 of file CloudViewer.cpp.
Transform rtabmap::CloudViewer::getTargetPose | ( | ) | const |
Definition at line 1335 of file CloudViewer.cpp.
unsigned int rtabmap::CloudViewer::getTrajectorySize | ( | ) | const |
Definition at line 1196 of file CloudViewer.cpp.
void rtabmap::CloudViewer::handleAction | ( | QAction * | event | ) | [protected, virtual] |
Definition at line 1993 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraFree | ( | ) | const |
Definition at line 1673 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraLockZ | ( | ) | const |
Definition at line 1677 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraTargetFollow | ( | ) | const |
Definition at line 1669 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraTargetLocked | ( | ) | const |
Definition at line 1665 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isFrustumShown | ( | ) | const |
Definition at line 1218 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isGridShown | ( | ) | const |
Definition at line 1681 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isTrajectoryShown | ( | ) | const |
Definition at line 1191 of file CloudViewer.cpp.
void rtabmap::CloudViewer::keyPressEvent | ( | QKeyEvent * | event | ) | [protected, virtual] |
Definition at line 1818 of file CloudViewer.cpp.
void rtabmap::CloudViewer::keyReleaseEvent | ( | QKeyEvent * | event | ) | [protected, virtual] |
Definition at line 1804 of file CloudViewer.cpp.
void rtabmap::CloudViewer::loadSettings | ( | QSettings & | settings, |
const QString & | group = "" |
||
) |
Definition at line 320 of file CloudViewer.cpp.
QMenu* rtabmap::CloudViewer::menu | ( | ) | [inline, protected] |
Definition at line 287 of file CloudViewer.h.
void rtabmap::CloudViewer::mouseMoveEvent | ( | QMouseEvent * | event | ) | [protected, virtual] |
Definition at line 1930 of file CloudViewer.cpp.
void rtabmap::CloudViewer::mousePressEvent | ( | QMouseEvent * | event | ) | [protected, virtual] |
Definition at line 1918 of file CloudViewer.cpp.
Definition at line 1311 of file CloudViewer.cpp.
Definition at line 901 of file CloudViewer.cpp.
Definition at line 1067 of file CloudViewer.cpp.
Definition at line 1127 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllLines | ( | ) |
Definition at line 965 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllTexts | ( | ) |
Definition at line 1181 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::removeCloud | ( | const std::string & | id | ) |
Definition at line 1318 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeCoordinate | ( | const std::string & | id | ) |
Definition at line 881 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeFrustum | ( | const std::string & | id | ) |
Definition at line 1052 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeGraph | ( | const std::string & | id | ) |
Definition at line 1111 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeGrid | ( | ) | [private] |
Definition at line 1760 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeLine | ( | const std::string & | id | ) |
Definition at line 950 of file CloudViewer.cpp.
Definition at line 830 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeOctomap | ( | ) |
Definition at line 747 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeText | ( | const std::string & | id | ) |
Definition at line 1166 of file CloudViewer.cpp.
void rtabmap::CloudViewer::resetCamera | ( | ) |
Definition at line 1280 of file CloudViewer.cpp.
void rtabmap::CloudViewer::saveSettings | ( | QSettings & | settings, |
const QString & | group = "" |
||
) | const |
Definition at line 266 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setBackfaceCulling | ( | bool | enabled, |
bool | frontfaceCulling | ||
) |
Definition at line 1344 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setBackgroundColor | ( | const QColor & | color | ) | [slot] |
Definition at line 1575 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraFree | ( | ) |
Definition at line 1640 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraLockZ | ( | bool | enabled = true | ) |
Definition at line 1646 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 1381 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraTargetFollow | ( | bool | enabled = true | ) |
Definition at line 1635 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraTargetLocked | ( | bool | enabled = true | ) |
Definition at line 1630 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCloudOpacity | ( | const std::string & | id, |
double | opacity = 1.0 |
||
) | [slot] |
Definition at line 1610 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCloudPointSize | ( | const std::string & | id, |
int | size | ||
) | [slot] |
Definition at line 1620 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCloudVisibility | ( | const std::string & | id, |
bool | isVisible | ||
) | [slot] |
Definition at line 1581 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setDefaultBackgroundColor | ( | const QColor & | color | ) | [slot] |
Definition at line 1561 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setFrustumColor | ( | QColor | value | ) |
Definition at line 1263 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setFrustumScale | ( | float | value | ) |
Definition at line 1258 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setFrustumShown | ( | bool | shown | ) |
Definition at line 1233 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridCellCount | ( | unsigned int | count | ) |
Definition at line 1698 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridCellSize | ( | float | size | ) |
Definition at line 1714 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridShown | ( | bool | shown | ) |
Definition at line 1652 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setRenderingRate | ( | double | rate | ) |
Definition at line 1350 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setTrajectoryShown | ( | bool | shown | ) |
Definition at line 1201 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setTrajectorySize | ( | unsigned int | value | ) |
Definition at line 1206 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setWorkingDirectory | ( | const QString & | path | ) | [inline] |
Definition at line 266 of file CloudViewer.h.
void rtabmap::CloudViewer::updateCameraFrustum | ( | const Transform & | pose, |
const StereoCameraModel & | model | ||
) |
Definition at line 1511 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraFrustum | ( | const Transform & | pose, |
const CameraModel & | model | ||
) |
Definition at line 1518 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraFrustums | ( | const Transform & | pose, |
const std::vector< CameraModel > & | models | ||
) |
Definition at line 1525 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraTargetPosition | ( | const Transform & | pose | ) |
Definition at line 1390 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateCloudPose | ( | const std::string & | id, |
const Transform & | pose | ||
) |
Definition at line 366 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateCoordinatePose | ( | const std::string & | id, |
const Transform & | transform | ||
) |
Definition at line 865 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateFrustumPose | ( | const std::string & | id, |
const Transform & | pose | ||
) |
Definition at line 1040 of file CloudViewer.cpp.
void rtabmap::CloudViewer::wheelEvent | ( | QWheelEvent * | event | ) | [protected, virtual] |
Definition at line 1971 of file CloudViewer.cpp.
QAction* rtabmap::CloudViewer::_aClearTrajectory [private] |
Definition at line 302 of file CloudViewer.h.
QMap<std::string, Transform> rtabmap::CloudViewer::_addedClouds [private] |
Definition at line 325 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aFollowCamera [private] |
Definition at line 297 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aLockCamera [private] |
Definition at line 296 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aLockViewZ [private] |
Definition at line 299 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aResetCamera [private] |
Definition at line 298 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetBackgroundColor [private] |
Definition at line 309 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetFrustumColor [private] |
Definition at line 305 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetFrustumScale [private] |
Definition at line 304 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetGridCellCount [private] |
Definition at line 307 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetGridCellSize [private] |
Definition at line 308 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetRenderingRate [private] |
Definition at line 310 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetTrajectorySize [private] |
Definition at line 301 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aShowFrustum [private] |
Definition at line 303 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aShowGrid [private] |
Definition at line 306 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aShowTrajectory [private] |
Definition at line 300 of file CloudViewer.h.
bool rtabmap::CloudViewer::_backfaceCulling [private] |
Definition at line 332 of file CloudViewer.h.
std::set<std::string> rtabmap::CloudViewer::_coordinates [private] |
Definition at line 313 of file CloudViewer.h.
QColor rtabmap::CloudViewer::_currentBgColor [private] |
Definition at line 331 of file CloudViewer.h.
QColor rtabmap::CloudViewer::_defaultBgColor [private] |
Definition at line 330 of file CloudViewer.h.
bool rtabmap::CloudViewer::_frontfaceCulling [private] |
Definition at line 333 of file CloudViewer.h.
QColor rtabmap::CloudViewer::_frustumColor [private] |
Definition at line 320 of file CloudViewer.h.
std::set<std::string> rtabmap::CloudViewer::_frustums [private] |
Definition at line 316 of file CloudViewer.h.
float rtabmap::CloudViewer::_frustumScale [private] |
Definition at line 319 of file CloudViewer.h.
std::set<std::string> rtabmap::CloudViewer::_graphes [private] |
Definition at line 312 of file CloudViewer.h.
unsigned int rtabmap::CloudViewer::_gridCellCount [private] |
Definition at line 321 of file CloudViewer.h.
float rtabmap::CloudViewer::_gridCellSize [private] |
Definition at line 322 of file CloudViewer.h.
std::list<std::string> rtabmap::CloudViewer::_gridLines [private] |
Definition at line 327 of file CloudViewer.h.
QSet<Qt::Key> rtabmap::CloudViewer::_keysPressed [private] |
Definition at line 328 of file CloudViewer.h.
cv::Vec3d rtabmap::CloudViewer::_lastCameraOrientation [private] |
Definition at line 323 of file CloudViewer.h.
cv::Vec3d rtabmap::CloudViewer::_lastCameraPose [private] |
Definition at line 324 of file CloudViewer.h.
Transform rtabmap::CloudViewer::_lastPose [private] |
Definition at line 326 of file CloudViewer.h.
std::set<std::string> rtabmap::CloudViewer::_lines [private] |
Definition at line 315 of file CloudViewer.h.
unsigned int rtabmap::CloudViewer::_maxTrajectorySize [private] |
Definition at line 318 of file CloudViewer.h.
QMenu* rtabmap::CloudViewer::_menu [private] |
Definition at line 311 of file CloudViewer.h.
vtkProp* rtabmap::CloudViewer::_octomapActor [private] |
Definition at line 335 of file CloudViewer.h.
double rtabmap::CloudViewer::_renderingRate [private] |
Definition at line 334 of file CloudViewer.h.
std::set<std::string> rtabmap::CloudViewer::_texts [private] |
Definition at line 314 of file CloudViewer.h.
pcl::PointCloud<pcl::PointXYZ>::Ptr rtabmap::CloudViewer::_trajectory [private] |
Definition at line 317 of file CloudViewer.h.
pcl::visualization::PCLVisualizer* rtabmap::CloudViewer::_visualizer [private] |
Definition at line 295 of file CloudViewer.h.
QString rtabmap::CloudViewer::_workingDirectory [private] |
Definition at line 329 of file CloudViewer.h.