#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, 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::PointXYZ >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor()) |
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::PolygonMesh::Ptr &mesh, const Transform &pose=Transform::getIdentity()) |
bool | addOccupancyGridMap (const cv::Mat &map8U, float resolution, float xMin, float yMin, float opacity) |
bool | addOrUpdateCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor()) |
bool | addOrUpdateCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor()) |
void | addOrUpdateGraph (const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &graph, const QColor &color=Qt::gray) |
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 |
unsigned int | getGridCellCount () const |
float | getGridCellSize () const |
bool | getPose (const std::string &id, Transform &pose) |
Transform | getTargetPose () const |
unsigned int | getTrajectorySize () const |
bool | isCameraFree () const |
bool | isCameraLockZ () const |
bool | isCameraTargetFollow () const |
bool | isCameraTargetLocked () const |
bool | isGridShown () const |
bool | isTrajectoryShown () const |
void | loadSettings (QSettings &settings, const QString &group="") |
void | removeAllClouds () |
void | removeAllGraphs () |
bool | removeCloud (const std::string &id) |
void | removeGraph (const std::string &id) |
void | removeOccupancyGridMap () |
void | saveSettings (QSettings &settings, const QString &group="") const |
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 | setGridCellCount (unsigned int count) |
void | setGridCellSize (float size) |
void | setGridShown (bool shown) |
void | setTrajectoryShown (bool shown) |
void | setTrajectorySize (unsigned int value) |
void | setWorkingDirectory (const QString &path) |
void | updateCameraTargetPosition (const Transform &pose) |
bool | updateCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZRGB >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor()) |
bool | updateCloud (const std::string &id, const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &pose=Transform::getIdentity(), const QColor &color=QColor()) |
bool | updateCloudPose (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) |
Private Member Functions | |
void | addGrid () |
void | createMenu () |
void | mouseEventOccurred (const pcl::visualization::MouseEvent &event, void *viewer_void) |
void | removeGrid () |
Private Attributes | |
QAction * | _aClearTrajectory |
QMap< std::string, Transform > | _addedClouds |
QAction * | _aFollowCamera |
QAction * | _aLockCamera |
QAction * | _aLockViewZ |
QAction * | _aResetCamera |
QAction * | _aSetBackgroundColor |
QAction * | _aSetGridCellCount |
QAction * | _aSetGridCellSize |
QAction * | _aSetTrajectorySize |
QAction * | _aShowGrid |
QAction * | _aShowTrajectory |
QColor | _currentBgColor |
QColor | _defaultBgColor |
std::set< std::string > | _graphes |
unsigned int | _gridCellCount |
float | _gridCellSize |
std::list< std::string > | _gridLines |
QSet< Qt::Key > | _keysPressed |
Transform | _lastPose |
unsigned int | _maxTrajectorySize |
QMenu * | _menu |
pcl::PointCloud< pcl::PointXYZ > ::Ptr | _trajectory |
pcl::visualization::PCLVisualizer * | _visualizer |
QString | _workingDirectory |
Definition at line 59 of file CloudViewer.h.
rtabmap::CloudViewer::CloudViewer | ( | QWidget * | parent = 0 | ) |
Definition at line 59 of file CloudViewer.cpp.
rtabmap::CloudViewer::~CloudViewer | ( | ) | [virtual] |
Definition at line 103 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addCloud | ( | const std::string & | id, |
const pcl::PCLPointCloud2Ptr & | binaryCloud, | ||
const Transform & | pose, | ||
bool | rgb, | ||
const QColor & | color = QColor() |
||
) |
Definition at line 336 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 389 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 406 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 423 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 442 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addGrid | ( | ) | [private] |
Definition at line 970 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addOccupancyGridMap | ( | const cv::Mat & | map8U, |
float | resolution, | ||
float | xMin, | ||
float | yMin, | ||
float | opacity | ||
) |
Definition at line 460 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addOrUpdateCloud | ( | const std::string & | id, |
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, | ||
const Transform & | pose = Transform::getIdentity() , |
||
const QColor & | color = QColor() |
||
) |
Definition at line 310 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addOrUpdateCloud | ( | const std::string & | id, |
const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, | ||
const Transform & | pose = Transform::getIdentity() , |
||
const QColor & | color = QColor() |
||
) |
Definition at line 323 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 540 of file CloudViewer.cpp.
virtual void rtabmap::CloudViewer::clear | ( | ) | [inline, virtual, slot] |
Definition at line 193 of file CloudViewer.h.
Definition at line 620 of file CloudViewer.cpp.
void rtabmap::CloudViewer::configChanged | ( | ) | [signal] |
void rtabmap::CloudViewer::contextMenuEvent | ( | QContextMenuEvent * | event | ) | [protected, virtual] |
Definition at line 1189 of file CloudViewer.cpp.
void rtabmap::CloudViewer::createMenu | ( | ) | [private] |
Definition at line 111 of file CloudViewer.cpp.
const QMap<std::string, Transform>& rtabmap::CloudViewer::getAddedClouds | ( | ) | const [inline] |
Definition at line 158 of file CloudViewer.h.
const QColor & rtabmap::CloudViewer::getBackgroundColor | ( | ) | const |
Definition at line 815 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 660 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::getCloudVisibility | ( | const std::string & | id | ) |
Definition at line 840 of file CloudViewer.cpp.
const QColor & rtabmap::CloudViewer::getDefaultBackgroundColor | ( | ) | const |
Definition at line 801 of file CloudViewer.cpp.
unsigned int rtabmap::CloudViewer::getGridCellCount | ( | ) | const |
Definition at line 929 of file CloudViewer.cpp.
float rtabmap::CloudViewer::getGridCellSize | ( | ) | const |
Definition at line 933 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::getPose | ( | const std::string & | id, |
Transform & | pose | ||
) |
Definition at line 641 of file CloudViewer.cpp.
Transform rtabmap::CloudViewer::getTargetPose | ( | ) | const |
Definition at line 651 of file CloudViewer.cpp.
unsigned int rtabmap::CloudViewer::getTrajectorySize | ( | ) | const |
Definition at line 605 of file CloudViewer.cpp.
void rtabmap::CloudViewer::handleAction | ( | QAction * | event | ) | [protected, virtual] |
Definition at line 1199 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraFree | ( | ) | const |
Definition at line 917 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraLockZ | ( | ) | const |
Definition at line 921 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraTargetFollow | ( | ) | const |
Definition at line 913 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraTargetLocked | ( | ) | const |
Definition at line 909 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isGridShown | ( | ) | const |
Definition at line 925 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isTrajectoryShown | ( | ) | const |
Definition at line 600 of file CloudViewer.cpp.
void rtabmap::CloudViewer::keyPressEvent | ( | QKeyEvent * | event | ) | [protected, virtual] |
Definition at line 1055 of file CloudViewer.cpp.
void rtabmap::CloudViewer::keyReleaseEvent | ( | QKeyEvent * | event | ) | [protected, virtual] |
Definition at line 1041 of file CloudViewer.cpp.
void rtabmap::CloudViewer::loadSettings | ( | QSettings & | settings, |
const QString & | group = "" |
||
) |
Definition at line 216 of file CloudViewer.cpp.
QMenu* rtabmap::CloudViewer::menu | ( | ) | [inline, protected] |
Definition at line 205 of file CloudViewer.h.
void rtabmap::CloudViewer::mouseEventOccurred | ( | const pcl::visualization::MouseEvent & | event, |
void * | viewer_void | ||
) | [private] |
Definition at line 50 of file CloudViewer.cpp.
void rtabmap::CloudViewer::mouseMoveEvent | ( | QMouseEvent * | event | ) | [protected, virtual] |
Definition at line 1167 of file CloudViewer.cpp.
void rtabmap::CloudViewer::mousePressEvent | ( | QMouseEvent * | event | ) | [protected, virtual] |
Definition at line 1155 of file CloudViewer.cpp.
Definition at line 627 of file CloudViewer.cpp.
Definition at line 590 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::removeCloud | ( | const std::string & | id | ) |
Definition at line 634 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeGraph | ( | const std::string & | id | ) |
Definition at line 574 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeGrid | ( | ) | [private] |
Definition at line 997 of file CloudViewer.cpp.
Definition at line 530 of file CloudViewer.cpp.
void rtabmap::CloudViewer::saveSettings | ( | QSettings & | settings, |
const QString & | group = "" |
||
) | const |
Definition at line 167 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setBackgroundColor | ( | const QColor & | color | ) | [slot] |
Definition at line 820 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraFree | ( | ) |
Definition at line 885 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraLockZ | ( | bool | enabled = true | ) |
Definition at line 891 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 678 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraTargetFollow | ( | bool | enabled = true | ) |
Definition at line 880 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraTargetLocked | ( | bool | enabled = true | ) |
Definition at line 875 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCloudOpacity | ( | const std::string & | id, |
double | opacity = 1.0 |
||
) | [slot] |
Definition at line 855 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCloudPointSize | ( | const std::string & | id, |
int | size | ||
) | [slot] |
Definition at line 865 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCloudVisibility | ( | const std::string & | id, |
bool | isVisible | ||
) | [slot] |
Definition at line 826 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setDefaultBackgroundColor | ( | const QColor & | color | ) | [slot] |
Definition at line 806 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridCellCount | ( | unsigned int | count | ) |
Definition at line 938 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridCellSize | ( | float | size | ) |
Definition at line 954 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridShown | ( | bool | shown | ) |
Definition at line 896 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setTrajectoryShown | ( | bool | shown | ) |
Definition at line 610 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setTrajectorySize | ( | unsigned int | value | ) |
Definition at line 615 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setWorkingDirectory | ( | const QString & | path | ) | [inline] |
Definition at line 185 of file CloudViewer.h.
void rtabmap::CloudViewer::updateCameraTargetPosition | ( | const Transform & | pose | ) |
Definition at line 686 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateCloud | ( | const std::string & | id, |
const pcl::PointCloud< pcl::PointXYZRGB >::Ptr & | cloud, | ||
const Transform & | pose = Transform::getIdentity() , |
||
const QColor & | color = QColor() |
||
) |
Definition at line 270 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateCloud | ( | const std::string & | id, |
const pcl::PointCloud< pcl::PointXYZ >::Ptr & | cloud, | ||
const Transform & | pose = Transform::getIdentity() , |
||
const QColor & | color = QColor() |
||
) |
Definition at line 290 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateCloudPose | ( | const std::string & | id, |
const Transform & | pose | ||
) |
Definition at line 253 of file CloudViewer.cpp.
QAction* rtabmap::CloudViewer::_aClearTrajectory [private] |
Definition at line 221 of file CloudViewer.h.
QMap<std::string, Transform> rtabmap::CloudViewer::_addedClouds [private] |
Definition at line 232 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aFollowCamera [private] |
Definition at line 216 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aLockCamera [private] |
Definition at line 215 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aLockViewZ [private] |
Definition at line 218 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aResetCamera [private] |
Definition at line 217 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetBackgroundColor [private] |
Definition at line 225 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetGridCellCount [private] |
Definition at line 223 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetGridCellSize [private] |
Definition at line 224 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aSetTrajectorySize [private] |
Definition at line 220 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aShowGrid [private] |
Definition at line 222 of file CloudViewer.h.
QAction* rtabmap::CloudViewer::_aShowTrajectory [private] |
Definition at line 219 of file CloudViewer.h.
QColor rtabmap::CloudViewer::_currentBgColor [private] |
Definition at line 238 of file CloudViewer.h.
QColor rtabmap::CloudViewer::_defaultBgColor [private] |
Definition at line 237 of file CloudViewer.h.
std::set<std::string> rtabmap::CloudViewer::_graphes [private] |
Definition at line 227 of file CloudViewer.h.
unsigned int rtabmap::CloudViewer::_gridCellCount [private] |
Definition at line 230 of file CloudViewer.h.
float rtabmap::CloudViewer::_gridCellSize [private] |
Definition at line 231 of file CloudViewer.h.
std::list<std::string> rtabmap::CloudViewer::_gridLines [private] |
Definition at line 234 of file CloudViewer.h.
QSet<Qt::Key> rtabmap::CloudViewer::_keysPressed [private] |
Definition at line 235 of file CloudViewer.h.
Transform rtabmap::CloudViewer::_lastPose [private] |
Definition at line 233 of file CloudViewer.h.
unsigned int rtabmap::CloudViewer::_maxTrajectorySize [private] |
Definition at line 229 of file CloudViewer.h.
QMenu* rtabmap::CloudViewer::_menu [private] |
Definition at line 226 of file CloudViewer.h.
pcl::PointCloud<pcl::PointXYZ>::Ptr rtabmap::CloudViewer::_trajectory [private] |
Definition at line 228 of file CloudViewer.h.
pcl::visualization::PCLVisualizer* rtabmap::CloudViewer::_visualizer [private] |
Definition at line 214 of file CloudViewer.h.
QString rtabmap::CloudViewer::_workingDirectory [private] |
Definition at line 236 of file CloudViewer.h.