Definition at line 31 of file mapper.cpp.
typedef boost::unique_future<PM::DataPoints*> Mapper::MapBuildingFuture [private] | 
        
Definition at line 54 of file mapper.cpp.
typedef boost::packaged_task<PM::DataPoints*> Mapper::MapBuildingTask [private] | 
        
Definition at line 53 of file mapper.cpp.
| Mapper::Mapper | ( | ros::NodeHandle & | n, | 
| ros::NodeHandle & | pn | ||
| ) | 
Definition at line 99 of file mapper.cpp.
| Mapper::~Mapper | ( | ) | 
Definition at line 191 of file mapper.cpp.
| bool Mapper::getPointMap | ( | map_msgs::GetPointMap::Request & | req, | 
| map_msgs::GetPointMap::Response & | res | ||
| ) |  [protected] | 
        
Definition at line 436 of file mapper.cpp.
| void Mapper::gotCloud | ( | const sensor_msgs::PointCloud2 & | cloudMsgIn | ) |  [protected] | 
        
Definition at line 217 of file mapper.cpp.
| void Mapper::gotScan | ( | const sensor_msgs::LaserScan & | scanMsgIn | ) |  [protected] | 
        
Definition at line 210 of file mapper.cpp.
| void Mapper::processCloud | ( | unique_ptr< DP > | cloud, | 
| const std::string & | scannerFrame, | ||
| const ros::Time & | stamp, | ||
| uint32_t | seq | ||
| ) |  [protected] | 
        
Definition at line 223 of file mapper.cpp.
| void Mapper::processNewMapIfAvailable | ( | ) |  [protected] | 
        
Definition at line 367 of file mapper.cpp.
| void Mapper::publishLoop | ( | double | publishPeriod | ) |  [protected] | 
        
Definition at line 417 of file mapper.cpp.
| void Mapper::publishTransform | ( | ) |  [protected] | 
        
Definition at line 429 of file mapper.cpp.
| bool Mapper::reset | ( | std_srvs::Empty::Request & | req, | 
| std_srvs::Empty::Response & | res | ||
| ) |  [protected] | 
        
Definition at line 462 of file mapper.cpp.
| bool Mapper::saveMap | ( | map_msgs::SaveMap::Request & | req, | 
| map_msgs::SaveMap::Response & | res | ||
| ) |  [protected] | 
        
Definition at line 445 of file mapper.cpp.
| void Mapper::setMap | ( | DP * | newPointCloud | ) |  [protected] | 
        
Definition at line 377 of file mapper.cpp.
| DP * Mapper::updateMap | ( | DP * | newPointCloud, | 
| const PM::TransformationParameters | Ticp, | ||
| bool | updateExisting | ||
| ) |  [protected] | 
        
Definition at line 392 of file mapper.cpp.
bool Mapper::changeModel [private] | 
        
Definition at line 59 of file mapper.cpp.
ros::Subscriber Mapper::cloudSub [private] | 
        
Definition at line 37 of file mapper.cpp.
ros::ServiceServer Mapper::getPointMapSrv [private] | 
        
Definition at line 40 of file mapper.cpp.
PM::ICPSequence Mapper::icp [private] | 
        
Definition at line 50 of file mapper.cpp.
PM::DataPointsFilters Mapper::inputFilters [private] | 
        
Definition at line 44 of file mapper.cpp.
MapBuildingFuture Mapper::mapBuildingFuture [private] | 
        
Definition at line 57 of file mapper.cpp.
bool Mapper::mapBuildingInProgress [private] | 
        
Definition at line 58 of file mapper.cpp.
MapBuildingTask Mapper::mapBuildingTask [private] | 
        
Definition at line 56 of file mapper.cpp.
boost::thread Mapper::mapBuildingThread [private] | 
        
Definition at line 55 of file mapper.cpp.
ros::Time Mapper::mapCreationTime [private] | 
        
Definition at line 48 of file mapper.cpp.
string Mapper::mapFrame [private] | 
        
Definition at line 68 of file mapper.cpp.
PM::DataPoints* Mapper::mapPointCloud [private] | 
        
Definition at line 49 of file mapper.cpp.
PM::DataPointsFilters Mapper::mapPostFilters [private] | 
        
Definition at line 46 of file mapper.cpp.
PM::DataPointsFilters Mapper::mapPreFilters [private] | 
        
Definition at line 45 of file mapper.cpp.
ros::Publisher Mapper::mapPub [private] | 
        
Definition at line 38 of file mapper.cpp.
double Mapper::maxOverlapToMerge [private] | 
        
Definition at line 65 of file mapper.cpp.
int Mapper::minMapPointCount [private] | 
        
Definition at line 63 of file mapper.cpp.
double Mapper::minOverlap [private] | 
        
Definition at line 64 of file mapper.cpp.
int Mapper::minReadingPointCount [private] | 
        
Definition at line 62 of file mapper.cpp.
ros::NodeHandle& Mapper::n [private] | 
        
Definition at line 33 of file mapper.cpp.
string Mapper::odomFrame [private] | 
        
Definition at line 67 of file mapper.cpp.
ros::Publisher Mapper::odomPub [private] | 
        
Definition at line 39 of file mapper.cpp.
ros::NodeHandle& Mapper::pn [private] | 
        
Definition at line 34 of file mapper.cpp.
boost::mutex Mapper::publishLock [private] | 
        
Definition at line 74 of file mapper.cpp.
boost::thread Mapper::publishThread [private] | 
        
Definition at line 73 of file mapper.cpp.
ros::ServiceServer Mapper::resetSrv [private] | 
        
Definition at line 42 of file mapper.cpp.
ros::ServiceServer Mapper::saveMapSrv [private] | 
        
Definition at line 41 of file mapper.cpp.
ros::Subscriber Mapper::scanSub [private] | 
        
Definition at line 36 of file mapper.cpp.
Definition at line 77 of file mapper.cpp.
tf::TransformListener Mapper::tfListener [private] | 
        
Definition at line 76 of file mapper.cpp.
double Mapper::tfPublishPeriod [private] | 
        
Definition at line 66 of file mapper.cpp.
Definition at line 72 of file mapper.cpp.
unique_ptr<PM::Transformation> Mapper::transformation [private] | 
        
Definition at line 47 of file mapper.cpp.
bool Mapper::useConstMotionModel [private] | 
        
Definition at line 70 of file mapper.cpp.
string Mapper::vtkFinalMapName [private] | 
        
name of the final vtk map
Definition at line 69 of file mapper.cpp.