#include <ndt_viz.h>
Public Member Functions | |
| void | addParticle (float x, float y, float z, float R=1.0, float G=1.0, float B=1.0) |
| void | addScan (Eigen::Vector3d orig, pcl::PointCloud< PointT > &cloud, double R=1.0, double G=1.0, double B=1.0) |
| void | addTrajectoryPoint (float x, float y, float z, float R=1.0, float G=1.0, float B=1.0) |
| void | clear () |
| void | clearParticles () |
| void | clearTrajectoryPoints () |
| void | displayParticles () |
| void | displayTrajectory () |
| void | ndtCoolCam (lslgeneric::NDTMap< PointT > *map, const Eigen::Affine3d &spos, double maxDist=70.0, unsigned int Nx=800, unsigned int Ny=600, double fx=800, double fy=600) |
| NDTViz (bool allocate_new_window=true) | |
| void | plotLocalConflictNDTMap (lslgeneric::NDTMap< PointT > *map, pcl::PointCloud< PointT > &cloud, double resolution, double R=1, double G=0, double B=0, bool heightCoding=false, double maxz=0) |
| void | plotLocalNDTMap (pcl::PointCloud< PointT > &cloud, double resolution, double R=0, double G=1, double B=0, bool heightCoding=true) |
| void | plotNDTMap (lslgeneric::NDTMap< PointT > *map, double R=1.0, double G=1.0, double B=1.0, bool heightCoding=false, bool setCameraPos=true) |
| void | plotNDTSAccordingToClass (float occupancy, lslgeneric::NDTMap< PointT > *map) |
| void | plotNDTSAccordingToCost (float occupancy, double MAX_COST, lslgeneric::NDTMap< PointT > *map) |
| void | plotNDTSAccordingToOccupancy (float occupancy, lslgeneric::NDTMap< PointT > *map) |
| void | plotNDTTraversabilityMap (lslgeneric::NDTMap< PointT > *map) |
| void | repaint () |
| void | setCameraPointing (double x, double y, double z) |
Public Attributes | |
| mrpt::opengl::CPointCloudColouredPtr | gl_particles |
| mrpt::opengl::CPointCloudColouredPtr | gl_points |
| mrpt::gui::CDisplayWindow3D * | win3D |
| void NDTViz< PointT >::addParticle | ( | float | x, |
| float | y, | ||
| float | z, | ||
| float | R = 1.0, |
||
| float | G = 1.0, |
||
| float | B = 1.0 |
||
| ) | [inline] |
| void NDTViz< PointT >::addScan | ( | Eigen::Vector3d | orig, |
| pcl::PointCloud< PointT > & | cloud, | ||
| double | R = 1.0, |
||
| double | G = 1.0, |
||
| double | B = 1.0 |
||
| ) | [inline] |
| void NDTViz< PointT >::addTrajectoryPoint | ( | float | x, |
| float | y, | ||
| float | z, | ||
| float | R = 1.0, |
||
| float | G = 1.0, |
||
| float | B = 1.0 |
||
| ) | [inline] |
| void NDTViz< PointT >::clearParticles | ( | ) | [inline] |
| void NDTViz< PointT >::clearTrajectoryPoints | ( | ) | [inline] |
| void NDTViz< PointT >::displayParticles | ( | ) | [inline] |
| void NDTViz< PointT >::displayTrajectory | ( | ) | [inline] |
| void NDTViz< PointT >::ndtCoolCam | ( | lslgeneric::NDTMap< PointT > * | map, |
| const Eigen::Affine3d & | spos, | ||
| double | maxDist = 70.0, |
||
| unsigned int | Nx = 800, |
||
| unsigned int | Ny = 600, |
||
| double | fx = 800, |
||
| double | fy = 600 |
||
| ) | [inline] |
| void NDTViz< PointT >::plotLocalConflictNDTMap | ( | lslgeneric::NDTMap< PointT > * | map, |
| pcl::PointCloud< PointT > & | cloud, | ||
| double | resolution, | ||
| double | R = 1, |
||
| double | G = 0, |
||
| double | B = 0, |
||
| bool | heightCoding = false, |
||
| double | maxz = 0 |
||
| ) | [inline] |
| void NDTViz< PointT >::plotLocalNDTMap | ( | pcl::PointCloud< PointT > & | cloud, |
| double | resolution, | ||
| double | R = 0, |
||
| double | G = 1, |
||
| double | B = 0, |
||
| bool | heightCoding = true |
||
| ) | [inline] |
| void NDTViz< PointT >::plotNDTMap | ( | lslgeneric::NDTMap< PointT > * | map, |
| double | R = 1.0, |
||
| double | G = 1.0, |
||
| double | B = 1.0, |
||
| bool | heightCoding = false, |
||
| bool | setCameraPos = true |
||
| ) | [inline] |
| void NDTViz< PointT >::plotNDTSAccordingToClass | ( | float | occupancy, |
| lslgeneric::NDTMap< PointT > * | map | ||
| ) | [inline] |
| void NDTViz< PointT >::plotNDTSAccordingToCost | ( | float | occupancy, |
| double | MAX_COST, | ||
| lslgeneric::NDTMap< PointT > * | map | ||
| ) | [inline] |
| void NDTViz< PointT >::plotNDTSAccordingToOccupancy | ( | float | occupancy, |
| lslgeneric::NDTMap< PointT > * | map | ||
| ) | [inline] |
| void NDTViz< PointT >::plotNDTTraversabilityMap | ( | lslgeneric::NDTMap< PointT > * | map | ) | [inline] |
| void NDTViz< PointT >::setCameraPointing | ( | double | x, |
| double | y, | ||
| double | z | ||
| ) | [inline] |
| mrpt::opengl::CPointCloudColouredPtr NDTViz< PointT >::gl_particles |