#include <general_slam.hpp>
| Public Member Functions | |
| virtual bool | compute () | 
| GeneralSLAM () | |
| virtual pcl::PointCloud< Point > ::ConstPtr | getMap () | 
| virtual void | setInputCloud (const PointCloudConstPtr &cloud) | 
| virtual void | setOdometry (const Eigen::Matrix4f &odometry) | 
| virtual | ~GeneralSLAM () | 
| Protected Member Functions | |
| virtual bool | compute_map ()=0 | 
| virtual bool | compute_registration ()=0 | 
| virtual bool | compute_transformation ()=0 | 
| Protected Attributes | |
| PointCloudConstPtr | input_ | 
| pcl::PointCloud< Point > | map_ | 
| Eigen::Matrix4f | odometry_ | 
Definition at line 65 of file general_slam.hpp.
| GeneralSLAM< Point >::GeneralSLAM | ( | ) |  [inline] | 
Definition at line 68 of file general_slam.hpp.
| virtual GeneralSLAM< Point >::~GeneralSLAM | ( | ) |  [inline, virtual] | 
Definition at line 71 of file general_slam.hpp.
| virtual bool GeneralSLAM< Point >::compute | ( | ) |  [inline, virtual] | 
Definition at line 85 of file general_slam.hpp.
| virtual bool GeneralSLAM< Point >::compute_map | ( | ) |  [protected, pure virtual] | 
| virtual bool GeneralSLAM< Point >::compute_registration | ( | ) |  [protected, pure virtual] | 
| virtual bool GeneralSLAM< Point >::compute_transformation | ( | ) |  [protected, pure virtual] | 
| virtual pcl::PointCloud<Point>::ConstPtr GeneralSLAM< Point >::getMap | ( | ) |  [inline, virtual] | 
Definition at line 81 of file general_slam.hpp.
| virtual void GeneralSLAM< Point >::setInputCloud | ( | const PointCloudConstPtr & | cloud | ) |  [inline, virtual] | 
Definition at line 73 of file general_slam.hpp.
| virtual void GeneralSLAM< Point >::setOdometry | ( | const Eigen::Matrix4f & | odometry | ) |  [inline, virtual] | 
Definition at line 77 of file general_slam.hpp.
| PointCloudConstPtr GeneralSLAM< Point >::input_  [protected] | 
Definition at line 100 of file general_slam.hpp.
| pcl::PointCloud<Point> GeneralSLAM< Point >::map_  [protected] | 
Definition at line 101 of file general_slam.hpp.
| Eigen::Matrix4f GeneralSLAM< Point >::odometry_  [protected] | 
Definition at line 102 of file general_slam.hpp.