Public Member Functions |
void | addParticle (float x, float y, float z, float R=1.0, float G=1.0, float 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 () |
Public Attributes |
mrpt::opengl::CPointCloudColouredPtr | gl_particles |
mrpt::opengl::CPointCloudColouredPtr | gl_points |
mrpt::gui::CDisplayWindow3D * | win3D |
template<typename PointT>
class NDTViz< PointT >
Definition at line 14 of file ndt_viz.h.
template<typename PointT>
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] |
Computes and visualizes an NDT depth image, based on maximum likelihood estimation
Orientation matrix, for rotating the camera to world frame
< direction vector based on camera model
Direction vector in world frame
Definition at line 444 of file ndt_viz.h.