Public Member Functions | Public Attributes | Protected Member Functions | Private Types | Private Attributes
MapMaintener Class Reference

List of all members.

Public Member Functions

 MapMaintener (ros::NodeHandle &n, ros::NodeHandle &pn)
 ~MapMaintener ()

Public Attributes

string mapFrame
string objectFrame
boost::mutex publishLock
PM::TransformationParameters TObjectToMap

Protected Member Functions

void addRotAndTransCtrl (InteractiveMarker &int_marker, const double w, const double x, const double y, const double z, const std::string name)
void gotCloud (const sensor_msgs::PointCloud2ConstPtr &cloudMsgIn, const nav_msgs::OdometryConstPtr &odom)
void makeMenuMarker (std::string name)
void pauseMapCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void processCloud (DP cloud, const TP TScannerToMap)
void saveMapCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void singleScanCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void startMapCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void stopMapCallback (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void update_tf (const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)

Private Types

typedef PM::DataPoints DP
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::PointCloud2,
nav_msgs::Odometry > 
MySyncPolicy
typedef PointMatcher< float > PM
typedef
PM::TransformationParameters 
TP

Private Attributes

message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
cloud_sub
ros::Subscriber cloudSub
MenuHandler::EntryHandle h_pause
MenuHandler::EntryHandle h_save
MenuHandler::EntryHandle h_single
MenuHandler::EntryHandle h_start
MenuHandler::EntryHandle h_stop
PM::ICP icp
PM::DataPointsFilters inputFilters
int inputQueueSize
bool mappingActive
PM::DataPoints mapPointCloud
PM::DataPointsFilters mapPostFilters
PM::DataPointsFilters mapPreFilters
ros::Publisher mapPub
MenuHandler menu_handler
ros::NodeHandlen
message_filters::Subscriber
< nav_msgs::Odometry > 
odom_sub
ros::NodeHandlepn
ros::Subscriber scanSub
boost::shared_ptr
< InteractiveMarkerServer
server
bool singleScan
const float size_x
const float size_y
const float size_z
message_filters::Synchronizer
< MySyncPolicy
sync
tf::TransformListener tfListener
unique_ptr< PM::Transformationtransformation
string vtkFinalMapName
 name of the final vtk map

Detailed Description

Definition at line 35 of file map_maintainer.cpp.


Member Typedef Documentation

typedef PM::DataPoints MapMaintener::DP [private]

Definition at line 38 of file map_maintainer.cpp.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, nav_msgs::Odometry> MapMaintener::MySyncPolicy [private]

Definition at line 47 of file map_maintainer.cpp.

typedef PointMatcher<float> MapMaintener::PM [private]

Definition at line 37 of file map_maintainer.cpp.

Definition at line 39 of file map_maintainer.cpp.


Constructor & Destructor Documentation

Definition at line 120 of file map_maintainer.cpp.

Definition at line 253 of file map_maintainer.cpp.


Member Function Documentation

void MapMaintener::addRotAndTransCtrl ( InteractiveMarker &  int_marker,
const double  w,
const double  x,
const double  y,
const double  z,
const std::string  name 
) [protected]

Definition at line 462 of file map_maintainer.cpp.

void MapMaintener::gotCloud ( const sensor_msgs::PointCloud2ConstPtr &  cloudMsgIn,
const nav_msgs::OdometryConstPtr &  odom 
) [protected]

Definition at line 266 of file map_maintainer.cpp.

void MapMaintener::makeMenuMarker ( std::string  name) [protected]

Definition at line 418 of file map_maintainer.cpp.

void MapMaintener::pauseMapCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 518 of file map_maintainer.cpp.

void MapMaintener::processCloud ( DP  cloud,
const TP  TScannerToMap 
) [protected]

Definition at line 283 of file map_maintainer.cpp.

void MapMaintener::saveMapCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 541 of file map_maintainer.cpp.

void MapMaintener::singleScanCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 503 of file map_maintainer.cpp.

void MapMaintener::startMapCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 508 of file map_maintainer.cpp.

void MapMaintener::stopMapCallback ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 528 of file map_maintainer.cpp.

void MapMaintener::update_tf ( const visualization_msgs::InteractiveMarkerFeedbackConstPtr &  feedback) [protected]

Definition at line 478 of file map_maintainer.cpp.


Member Data Documentation

message_filters::Subscriber<sensor_msgs::PointCloud2> MapMaintener::cloud_sub [private]

Definition at line 44 of file map_maintainer.cpp.

Definition at line 51 of file map_maintainer.cpp.

Definition at line 82 of file map_maintainer.cpp.

Definition at line 84 of file map_maintainer.cpp.

Definition at line 80 of file map_maintainer.cpp.

Definition at line 81 of file map_maintainer.cpp.

Definition at line 83 of file map_maintainer.cpp.

Definition at line 59 of file map_maintainer.cpp.

Definition at line 61 of file map_maintainer.cpp.

Definition at line 70 of file map_maintainer.cpp.

Definition at line 94 of file map_maintainer.cpp.

Definition at line 78 of file map_maintainer.cpp.

Definition at line 66 of file map_maintainer.cpp.

Definition at line 63 of file map_maintainer.cpp.

Definition at line 62 of file map_maintainer.cpp.

Definition at line 52 of file map_maintainer.cpp.

Definition at line 77 of file map_maintainer.cpp.

Definition at line 41 of file map_maintainer.cpp.

Definition at line 93 of file map_maintainer.cpp.

message_filters::Subscriber<nav_msgs::Odometry> MapMaintener::odom_sub [private]

Definition at line 45 of file map_maintainer.cpp.

Definition at line 42 of file map_maintainer.cpp.

Definition at line 90 of file map_maintainer.cpp.

Definition at line 50 of file map_maintainer.cpp.

boost::shared_ptr<InteractiveMarkerServer> MapMaintener::server [private]

Definition at line 76 of file map_maintainer.cpp.

bool MapMaintener::singleScan [private]

Definition at line 79 of file map_maintainer.cpp.

const float MapMaintener::size_x [private]

Definition at line 71 of file map_maintainer.cpp.

const float MapMaintener::size_y [private]

Definition at line 72 of file map_maintainer.cpp.

const float MapMaintener::size_z [private]

Definition at line 73 of file map_maintainer.cpp.

Definition at line 48 of file map_maintainer.cpp.

Definition at line 87 of file map_maintainer.cpp.

Definition at line 91 of file map_maintainer.cpp.

Definition at line 64 of file map_maintainer.cpp.

name of the final vtk map

Definition at line 69 of file map_maintainer.cpp.


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


ethzasl_icp_mapper
Author(s): François Pomerleau and Stéphane Magnenat
autogenerated on Mon Oct 6 2014 10:28:23