Functions | Variables
mcl_visualization.hpp File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Functions

void addMap2Scene (lslgeneric::NDTMap< pcl::PointXYZ > &map, Eigen::Vector3d &origin, mrpt::opengl::COpenGLScenePtr scene)
void addParticlesToWorld (mcl::CParticleFilter &pf, Eigen::Vector3d gt, Eigen::Vector3d dist_mean, Eigen::Vector3d odometry)
void addPointCloud2Scene (mrpt::opengl::COpenGLScenePtr scene, pcl::PointCloud< pcl::PointXYZ >::Ptr points)
void addPoseCovariance (double x, double y, Eigen::Matrix3d cov, mrpt::opengl::COpenGLScenePtr scene)
void addScanToScene (mrpt::opengl::COpenGLScenePtr scene, Eigen::Vector3d orig, pcl::PointCloud< pcl::PointXYZ >::Ptr cloud)
void initializeScene ()
mrpt::gui::CDisplayWindow3D win3D ("2D NDT-MCL Visualization", 800, 600)

Variables

mrpt::opengl::CPointCloudColouredPtr gl_particles = mrpt::opengl::CPointCloudColoured::Create()
mrpt::opengl::CPointCloudColouredPtr gl_points = mrpt::opengl::CPointCloudColoured::Create()
mrpt::opengl::CGridPlaneXYPtr plane = mrpt::opengl::CGridPlaneXY::Create()

Function Documentation

void addMap2Scene ( lslgeneric::NDTMap< pcl::PointXYZ > &  map,
Eigen::Vector3d &  origin,
mrpt::opengl::COpenGLScenePtr  scene 
)

Draw the ellipses in the map to the scene

And plot the results

Definition at line 26 of file mcl_visualization.hpp.

void addParticlesToWorld ( mcl::CParticleFilter pf,
Eigen::Vector3d  gt,
Eigen::Vector3d  dist_mean,
Eigen::Vector3d  odometry 
)

Draw particles

Definition at line 93 of file mcl_visualization.hpp.

void addPointCloud2Scene ( mrpt::opengl::COpenGLScenePtr  scene,
pcl::PointCloud< pcl::PointXYZ >::Ptr  points 
)

Definition at line 80 of file mcl_visualization.hpp.

void addPoseCovariance ( double  x,
double  y,
Eigen::Matrix3d  cov,
mrpt::opengl::COpenGLScenePtr  scene 
)

Definition at line 54 of file mcl_visualization.hpp.

void addScanToScene ( mrpt::opengl::COpenGLScenePtr  scene,
Eigen::Vector3d  orig,
pcl::PointCloud< pcl::PointXYZ >::Ptr  cloud 
)

Add the laser scan to the scen

Definition at line 70 of file mcl_visualization.hpp.

void initializeScene ( )

Definition at line 8 of file mcl_visualization.hpp.

mrpt::gui::CDisplayWindow3D win3D ( "2D NDT-MCL Visualization"  ,
800  ,
600   
)

Variable Documentation

mrpt::opengl::CPointCloudColouredPtr gl_particles = mrpt::opengl::CPointCloudColoured::Create()

Definition at line 4 of file mcl_visualization.hpp.

mrpt::opengl::CPointCloudColouredPtr gl_points = mrpt::opengl::CPointCloudColoured::Create()

Definition at line 3 of file mcl_visualization.hpp.

mrpt::opengl::CGridPlaneXYPtr plane = mrpt::opengl::CGridPlaneXY::Create()

Definition at line 2 of file mcl_visualization.hpp.



ndt_mcl
Author(s): Jari Saarinen
autogenerated on Mon Oct 6 2014 03:20:03