#include <CloudViewer.h>
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(), int viewport=1) |
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 | 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::PointXYZINormal >::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::PointXYZRGBNormal >::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 | addElevationMap (const cv::Mat &map32FC1, float resolution, float xMin, float yMin, float opacity) |
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 &pose, const Transform &localTransform, double scale, const QColor &color=QColor(), float fovX=1.1, float fovY=0.85) |
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) |
double | getCoordinateFrameScale () const |
const QColor & | getDefaultBackgroundColor () const |
QColor | getFrustumColor () const |
float | getFrustumScale () const |
unsigned int | getGridCellCount () const |
float | getGridCellSize () const |
std::string | getIdByActor (vtkProp *actor) const |
float | getIntensityMax () 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 | isBackfaceCulling () const |
bool | isCameraAxisShown () const |
bool | isCameraFree () const |
bool | isCameraLockZ () const |
bool | isCameraOrtho () const |
bool | isCameraTargetFollow () const |
bool | isCameraTargetLocked () const |
bool | isEdgeVisible () const |
bool | isEDLShadingOn () const |
bool | isFrontfaceCulling () const |
bool | isFrustumShown () const |
bool | isGridShown () const |
bool | isIntensityRainbowColormap () const |
bool | isIntensityRedColormap () const |
bool | isLightingOn () const |
bool | isNormalsShown () const |
bool | isPolygonPicking () const |
bool | isShadingOn () const |
bool | isTrajectoryShown () const |
void | loadSettings (QSettings &settings, const QString &group="") |
void | refreshView () |
void | removeAllClouds () |
void | removeAllCoordinates (const std::string &prefix="") |
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 | removeElevationMap () |
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 | setCameraAxisShown (bool shown) |
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 | setCoordinateFrameScale (double scale) |
void | setEdgeVisibility (bool visible) |
void | setEDLShading (bool on) |
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 | setIntensityMax (float value) |
void | setIntensityRainbowColormap (bool value) |
void | setIntensityRedColormap (bool value) |
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 CameraModel &model) |
void | updateCameraFrustum (const Transform &pose, const StereoCameraModel &model) |
void | updateCameraFrustums (const Transform &pose, const std::vector< CameraModel > &models) |
void | updateCameraFrustums (const Transform &pose, const std::vector< StereoCameraModel > &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 () |
Definition at line 79 of file CloudViewer.h.
rtabmap::CloudViewer::CloudViewer | ( | QWidget * | parent = 0 , |
CloudViewerInteractorStyle * | style = CloudViewerInteractorStyle::New() |
||
) |
Definition at line 101 of file CloudViewer.cpp.
|
virtual |
Definition at line 253 of file CloudViewer.cpp.
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() , |
||
int | viewport = 1 |
||
) |
Definition at line 745 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 901 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 912 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 890 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 879 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 868 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 857 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 923 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 961 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 999 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 1037 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 1074 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addElevationMap | ( | const cv::Mat & | map32FC1, |
float | resolution, | ||
float | xMin, | ||
float | yMin, | ||
float | opacity | ||
) |
Definition at line 1610 of file CloudViewer.cpp.
|
private |
Definition at line 3433 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addOccupancyGridMap | ( | const cv::Mat & | map8U, |
float | resolution, | ||
float | xMin, | ||
float | yMin, | ||
float | opacity | ||
) |
Definition at line 1530 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::addOctomap | ( | const OctoMap * | octomap, |
unsigned int | treeDepth = 0 , |
||
bool | volumeRepresentation = true |
||
) |
Definition at line 1113 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addOrUpdateCoordinate | ( | const std::string & | id, |
const Transform & | transform, | ||
double | scale, | ||
bool | foreground = false |
||
) |
Definition at line 1735 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 1932 of file CloudViewer.cpp.
void rtabmap::CloudViewer::addOrUpdateFrustum | ( | const std::string & | id, |
const Transform & | pose, | ||
const Transform & | localTransform, | ||
double | scale, | ||
const QColor & | color = QColor() , |
||
float | fovX = 1.1 , |
||
float | fovY = 0.85 |
||
) |
Definition at line 2146 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 2296 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 1810 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 1994 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 2005 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 1876 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 2359 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 1341 of file CloudViewer.cpp.
void rtabmap::CloudViewer::buildPickingLocator | ( | bool | enable | ) |
Definition at line 3571 of file CloudViewer.cpp.
|
virtualslot |
Definition at line 261 of file CloudViewer.cpp.
void rtabmap::CloudViewer::clearTrajectory | ( | ) |
Definition at line 2435 of file CloudViewer.cpp.
|
signal |
|
protectedvirtual |
Definition at line 3806 of file CloudViewer.cpp.
|
private |
Definition at line 285 of file CloudViewer.cpp.
|
inline |
Definition at line 338 of file CloudViewer.h.
|
inline |
Definition at line 226 of file CloudViewer.h.
|
inline |
Definition at line 260 of file CloudViewer.h.
|
inline |
Definition at line 295 of file CloudViewer.h.
|
inline |
Definition at line 237 of file CloudViewer.h.
|
inline |
Definition at line 280 of file CloudViewer.h.
|
inline |
Definition at line 247 of file CloudViewer.h.
|
inline |
Definition at line 313 of file CloudViewer.h.
const QColor & rtabmap::CloudViewer::getBackgroundColor | ( | ) | const |
Definition at line 3170 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 2913 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::getCloudVisibility | ( | const std::string & | id | ) |
Definition at line 3214 of file CloudViewer.cpp.
QColor rtabmap::CloudViewer::getColor | ( | const std::string & | id | ) |
Definition at line 2654 of file CloudViewer.cpp.
double rtabmap::CloudViewer::getCoordinateFrameScale | ( | ) | const |
Definition at line 2461 of file CloudViewer.cpp.
const QColor & rtabmap::CloudViewer::getDefaultBackgroundColor | ( | ) | const |
Definition at line 3156 of file CloudViewer.cpp.
QColor rtabmap::CloudViewer::getFrustumColor | ( | ) | const |
Definition at line 2481 of file CloudViewer.cpp.
float rtabmap::CloudViewer::getFrustumScale | ( | ) | const |
Definition at line 2476 of file CloudViewer.cpp.
unsigned int rtabmap::CloudViewer::getGridCellCount | ( | ) | const |
Definition at line 3393 of file CloudViewer.cpp.
float rtabmap::CloudViewer::getGridCellSize | ( | ) | const |
Definition at line 3397 of file CloudViewer.cpp.
std::string rtabmap::CloudViewer::getIdByActor | ( | vtkProp * | actor | ) | const |
Definition at line 2623 of file CloudViewer.cpp.
float rtabmap::CloudViewer::getIntensityMax | ( | ) | const |
Definition at line 3538 of file CloudViewer.cpp.
|
inline |
Definition at line 402 of file CloudViewer.h.
float rtabmap::CloudViewer::getNormalsScale | ( | ) | const |
Definition at line 3503 of file CloudViewer.cpp.
int rtabmap::CloudViewer::getNormalsStep | ( | ) | const |
Definition at line 3499 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::getPose | ( | const std::string & | id, |
Transform & | pose | ||
) |
Definition at line 2604 of file CloudViewer.cpp.
double rtabmap::CloudViewer::getRenderingRate | ( | ) | const |
Definition at line 3372 of file CloudViewer.cpp.
Transform rtabmap::CloudViewer::getTargetPose | ( | ) | const |
Definition at line 2614 of file CloudViewer.cpp.
unsigned int rtabmap::CloudViewer::getTrajectorySize | ( | ) | const |
Definition at line 2420 of file CloudViewer.cpp.
|
protectedvirtual |
Definition at line 3816 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isBackfaceCulling | ( | ) | const |
Definition at line 3344 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraAxisShown | ( | ) | const |
Definition at line 2442 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraFree | ( | ) | const |
Definition at line 3332 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraLockZ | ( | ) | const |
Definition at line 3336 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraOrtho | ( | ) | const |
Definition at line 3340 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraTargetFollow | ( | ) | const |
Definition at line 3328 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isCameraTargetLocked | ( | ) | const |
Definition at line 3324 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isEdgeVisible | ( | ) | const |
Definition at line 3368 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isEDLShadingOn | ( | ) | const |
Definition at line 3356 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isFrontfaceCulling | ( | ) | const |
Definition at line 3348 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isFrustumShown | ( | ) | const |
Definition at line 2471 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isGridShown | ( | ) | const |
Definition at line 3389 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isIntensityRainbowColormap | ( | ) | const |
Definition at line 3534 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isIntensityRedColormap | ( | ) | const |
Definition at line 3530 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isLightingOn | ( | ) | const |
Definition at line 3360 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isNormalsShown | ( | ) | const |
Definition at line 3495 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isPolygonPicking | ( | ) | const |
Definition at line 3352 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isShadingOn | ( | ) | const |
Definition at line 3364 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::isTrajectoryShown | ( | ) | const |
Definition at line 2415 of file CloudViewer.cpp.
|
protectedvirtual |
Definition at line 3625 of file CloudViewer.cpp.
|
protectedvirtual |
Definition at line 3611 of file CloudViewer.cpp.
void rtabmap::CloudViewer::loadSettings | ( | QSettings & | settings, |
const QString & | group = "" |
||
) |
Definition at line 480 of file CloudViewer.cpp.
|
inlineprotected |
Definition at line 424 of file CloudViewer.h.
|
protectedvirtual |
Definition at line 3735 of file CloudViewer.cpp.
|
protectedvirtual |
Definition at line 3723 of file CloudViewer.cpp.
void rtabmap::CloudViewer::refreshView | ( | ) |
Definition at line 538 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllClouds | ( | ) |
Definition at line 2575 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllCoordinates | ( | const std::string & | prefix = "" | ) |
Definition at line 1797 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllCubes | ( | ) |
Definition at line 1984 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllFrustums | ( | bool | exceptCameraReference = false | ) |
Definition at line 2283 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllGraphs | ( | ) |
Definition at line 2349 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllLines | ( | ) |
Definition at line 1866 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllQuads | ( | ) |
Definition at line 2126 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllSpheres | ( | ) |
Definition at line 1922 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeAllTexts | ( | ) |
Definition at line 2405 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::removeCloud | ( | const std::string & | id | ) |
Definition at line 2588 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeCoordinate | ( | const std::string & | id | ) |
Definition at line 1777 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeCube | ( | const std::string & | id | ) |
Definition at line 1969 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeElevationMap | ( | ) |
Definition at line 1727 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeFrustum | ( | const std::string & | id | ) |
Definition at line 2268 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeGraph | ( | const std::string & | id | ) |
Definition at line 2333 of file CloudViewer.cpp.
|
private |
Definition at line 3473 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeLine | ( | const std::string & | id | ) |
Definition at line 1851 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeOccupancyGridMap | ( | ) |
Definition at line 1595 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeOctomap | ( | ) |
Definition at line 1324 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeQuad | ( | const std::string & | id | ) |
Definition at line 2111 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeSphere | ( | const std::string & | id | ) |
Definition at line 1907 of file CloudViewer.cpp.
void rtabmap::CloudViewer::removeText | ( | const std::string & | id | ) |
Definition at line 2390 of file CloudViewer.cpp.
void rtabmap::CloudViewer::resetCamera | ( | ) |
Definition at line 2530 of file CloudViewer.cpp.
void rtabmap::CloudViewer::saveSettings | ( | QSettings & | settings, |
const QString & | group = "" |
||
) | const |
Definition at line 415 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setBackfaceCulling | ( | bool | enabled, |
bool | frontfaceCulling | ||
) |
Definition at line 2732 of file CloudViewer.cpp.
|
slot |
Definition at line 3175 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraAxisShown | ( | bool | shown | ) |
Definition at line 2447 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraFree | ( | ) |
Definition at line 3298 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraLockZ | ( | bool | enabled = true | ) |
Definition at line 3304 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraOrtho | ( | bool | enabled = true | ) |
Definition at line 3309 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 2938 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraTargetFollow | ( | bool | enabled = true | ) |
Definition at line 3293 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCameraTargetLocked | ( | bool | enabled = true | ) |
Definition at line 3288 of file CloudViewer.cpp.
|
slot |
Definition at line 3241 of file CloudViewer.cpp.
|
slot |
Definition at line 3249 of file CloudViewer.cpp.
|
slot |
Definition at line 3276 of file CloudViewer.cpp.
|
slot |
Definition at line 3181 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setColor | ( | const std::string & | id, |
const QColor & | color | ||
) |
Definition at line 2696 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setCoordinateFrameScale | ( | double | scale | ) |
Definition at line 2466 of file CloudViewer.cpp.
|
slot |
Definition at line 3161 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setEdgeVisibility | ( | bool | visible | ) |
Definition at line 2873 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setEDLShading | ( | bool | on | ) |
Definition at line 2794 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setFrustumColor | ( | QColor | value | ) |
Definition at line 2516 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setFrustumScale | ( | float | value | ) |
Definition at line 2511 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setFrustumShown | ( | bool | shown | ) |
Definition at line 2486 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridCellCount | ( | unsigned int | count | ) |
Definition at line 3401 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridCellSize | ( | float | size | ) |
Definition at line 3417 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setGridShown | ( | bool | shown | ) |
Definition at line 3377 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setIntensityMax | ( | float | value | ) |
Definition at line 3559 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setIntensityRainbowColormap | ( | bool | value | ) |
Definition at line 3551 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setIntensityRedColormap | ( | bool | value | ) |
Definition at line 3543 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setInteractorLayer | ( | int | layer | ) |
Definition at line 2895 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setLighting | ( | bool | on | ) |
Definition at line 2829 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setNormalsScale | ( | float | scale | ) |
Definition at line 3518 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setNormalsShown | ( | bool | shown | ) |
Definition at line 3482 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setNormalsStep | ( | int | step | ) |
Definition at line 3507 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setPolygonPicking | ( | bool | enabled | ) |
Definition at line 2758 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setRenderingRate | ( | double | rate | ) |
Definition at line 2788 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setShading | ( | bool | on | ) |
Definition at line 2851 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setTrajectoryShown | ( | bool | shown | ) |
Definition at line 2425 of file CloudViewer.cpp.
void rtabmap::CloudViewer::setTrajectorySize | ( | unsigned int | value | ) |
Definition at line 2430 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraFrustum | ( | const Transform & | pose, |
const CameraModel & | model | ||
) |
Definition at line 3108 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraFrustum | ( | const Transform & | pose, |
const StereoCameraModel & | model | ||
) |
Definition at line 3095 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraFrustums | ( | const Transform & | pose, |
const std::vector< CameraModel > & | models | ||
) |
Definition at line 3115 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraFrustums | ( | const Transform & | pose, |
const std::vector< StereoCameraModel > & | models | ||
) |
Definition at line 3140 of file CloudViewer.cpp.
void rtabmap::CloudViewer::updateCameraTargetPosition | ( | const Transform & | pose | ) |
Definition at line 2979 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateCloudPose | ( | const std::string & | id, |
const Transform & | pose | ||
) |
Definition at line 547 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateCoordinatePose | ( | const std::string & | id, |
const Transform & | transform | ||
) |
Definition at line 1761 of file CloudViewer.cpp.
bool rtabmap::CloudViewer::updateFrustumPose | ( | const std::string & | id, |
const Transform & | pose | ||
) |
Definition at line 2225 of file CloudViewer.cpp.
|
inlineprotected |
Definition at line 425 of file CloudViewer.h.
|
protectedvirtual |
Definition at line 3786 of file CloudViewer.cpp.
|
private |
Definition at line 462 of file CloudViewer.h.
|
private |
Definition at line 438 of file CloudViewer.h.
|
private |
Definition at line 441 of file CloudViewer.h.
|
private |
Definition at line 485 of file CloudViewer.h.
|
private |
Definition at line 435 of file CloudViewer.h.
|
private |
Definition at line 434 of file CloudViewer.h.
|
private |
Definition at line 437 of file CloudViewer.h.
|
private |
Definition at line 463 of file CloudViewer.h.
|
private |
Definition at line 436 of file CloudViewer.h.
|
private |
Definition at line 456 of file CloudViewer.h.
|
private |
Definition at line 461 of file CloudViewer.h.
|
private |
Definition at line 458 of file CloudViewer.h.
|
private |
Definition at line 460 of file CloudViewer.h.
|
private |
Definition at line 443 of file CloudViewer.h.
|
private |
Definition at line 446 of file CloudViewer.h.
|
private |
Definition at line 445 of file CloudViewer.h.
|
private |
Definition at line 448 of file CloudViewer.h.
|
private |
Definition at line 449 of file CloudViewer.h.
|
private |
Definition at line 455 of file CloudViewer.h.
|
private |
Definition at line 454 of file CloudViewer.h.
|
private |
Definition at line 453 of file CloudViewer.h.
|
private |
Definition at line 459 of file CloudViewer.h.
|
private |
Definition at line 452 of file CloudViewer.h.
|
private |
Definition at line 451 of file CloudViewer.h.
|
private |
Definition at line 457 of file CloudViewer.h.
|
private |
Definition at line 440 of file CloudViewer.h.
|
private |
Definition at line 442 of file CloudViewer.h.
|
private |
Definition at line 444 of file CloudViewer.h.
|
private |
Definition at line 447 of file CloudViewer.h.
|
private |
Definition at line 450 of file CloudViewer.h.
|
private |
Definition at line 439 of file CloudViewer.h.
|
private |
Definition at line 481 of file CloudViewer.h.
|
private |
Definition at line 495 of file CloudViewer.h.
|
private |
Definition at line 466 of file CloudViewer.h.
|
private |
Definition at line 470 of file CloudViewer.h.
|
private |
Definition at line 490 of file CloudViewer.h.
|
private |
Definition at line 489 of file CloudViewer.h.
|
private |
Definition at line 491 of file CloudViewer.h.
|
private |
Definition at line 476 of file CloudViewer.h.
|
private |
Definition at line 472 of file CloudViewer.h.
|
private |
Definition at line 475 of file CloudViewer.h.
|
private |
Definition at line 465 of file CloudViewer.h.
|
private |
Definition at line 477 of file CloudViewer.h.
|
private |
Definition at line 478 of file CloudViewer.h.
|
private |
Definition at line 487 of file CloudViewer.h.
|
private |
Definition at line 494 of file CloudViewer.h.
|
private |
Definition at line 488 of file CloudViewer.h.
|
private |
Definition at line 483 of file CloudViewer.h.
|
private |
Definition at line 484 of file CloudViewer.h.
|
private |
Definition at line 486 of file CloudViewer.h.
|
private |
Definition at line 468 of file CloudViewer.h.
|
private |
Definition at line 482 of file CloudViewer.h.
|
private |
Definition at line 474 of file CloudViewer.h.
|
private |
Definition at line 464 of file CloudViewer.h.
|
private |
Definition at line 480 of file CloudViewer.h.
|
private |
Definition at line 479 of file CloudViewer.h.
|
private |
Definition at line 493 of file CloudViewer.h.
|
private |
Definition at line 471 of file CloudViewer.h.
|
private |
Definition at line 492 of file CloudViewer.h.
|
private |
Definition at line 469 of file CloudViewer.h.
|
private |
Definition at line 467 of file CloudViewer.h.
|
private |
Definition at line 473 of file CloudViewer.h.
|
private |
Definition at line 433 of file CloudViewer.h.