Public Member Functions | Public Attributes
NDTViz< PointT > Class Template Reference

#include <ndt_viz.h>

List of all members.

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

Detailed Description

template<typename PointT>
class NDTViz< PointT >

Definition at line 14 of file ndt_viz.h.


Constructor & Destructor Documentation

template<typename PointT>
NDTViz< PointT >::NDTViz ( bool  allocate_new_window = true) [inline]

Definition at line 21 of file ndt_viz.h.


Member Function Documentation

template<typename PointT>
void NDTViz< PointT >::addParticle ( float  x,
float  y,
float  z,
float  R = 1.0,
float  G = 1.0,
float  B = 1.0 
) [inline]

Definition at line 65 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::addScan ( Eigen::Vector3d  orig,
pcl::PointCloud< PointT > &  cloud,
double  R = 1.0,
double  G = 1.0,
double  B = 1.0 
) [inline]

Add the laser scan to the scen

Definition at line 84 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::addTrajectoryPoint ( float  x,
float  y,
float  z,
float  R = 1.0,
float  G = 1.0,
float  B = 1.0 
) [inline]

Definition at line 53 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::clear ( ) [inline]

Definition at line 43 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::clearParticles ( ) [inline]

Definition at line 64 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::clearTrajectoryPoints ( ) [inline]

Definition at line 49 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::displayParticles ( ) [inline]

Definition at line 70 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::displayTrajectory ( ) [inline]

Definition at line 58 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 464 of file ndt_viz.h.

template<typename PointT>
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]

Definition at line 359 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::plotLocalNDTMap ( pcl::PointCloud< PointT > &  cloud,
double  resolution,
double  R = 0,
double  G = 1,
double  B = 0,
bool  heightCoding = true 
) [inline]

Definition at line 321 of file ndt_viz.h.

template<typename PointT>
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]

Definition at line 98 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::plotNDTSAccordingToClass ( float  occupancy,
lslgeneric::NDTMap< PointT > *  map 
) [inline]

plots ndts according to the cell class, with an occupancy cutoff

Definition at line 196 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::plotNDTSAccordingToCost ( float  occupancy,
double  MAX_COST,
lslgeneric::NDTMap< PointT > *  map 
) [inline]

Definition at line 142 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::plotNDTSAccordingToOccupancy ( float  occupancy,
lslgeneric::NDTMap< PointT > *  map 
) [inline]

Definition at line 270 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::plotNDTTraversabilityMap ( lslgeneric::NDTMap< PointT > *  map) [inline]

Definition at line 412 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::repaint ( ) [inline]

Definition at line 39 of file ndt_viz.h.

template<typename PointT>
void NDTViz< PointT >::setCameraPointing ( double  x,
double  y,
double  z 
) [inline]

Definition at line 75 of file ndt_viz.h.


Member Data Documentation

template<typename PointT>
mrpt::opengl::CPointCloudColouredPtr NDTViz< PointT >::gl_particles

Definition at line 19 of file ndt_viz.h.

template<typename PointT>
mrpt::opengl::CPointCloudColouredPtr NDTViz< PointT >::gl_points

Definition at line 18 of file ndt_viz.h.

template<typename PointT>
mrpt::gui::CDisplayWindow3D* NDTViz< PointT >::win3D

Definition at line 17 of file ndt_viz.h.


The documentation for this class was generated from the following file:


ndt_visualisation
Author(s): Todor Stoyanov, Jari Saarinen, Henrik Andreasson
autogenerated on Mon Oct 6 2014 03:19:48