Public Types | Public Member Functions | Protected Attributes
srs_env_model::CPcToOcRegistration Class Reference

#include <CPCtoOCRegistration.h>

List of all members.

Public Types

typedef sensor_msgs::PointCloud2 tCloud
 Used cloud.
typedef CPclRegistration
< tPclPoint, tPclPoint > 
tRegistrator
 Registration module type.

Public Member Functions

 CPcToOcRegistration ()
 Constructor.
Eigen::Matrix4f getTransform ()
 Get transform.
virtual void init (ros::NodeHandle &node_handle)
 Initialize plugin - called in server constructor.
bool isRegistering ()
 Is some registering mode set.
bool registerCloud (tPointCloudPtr &cloud, const SMapWithParameters &map)
 Register cloud to the octomap.

Protected Attributes

pcl::VoxelGrid< tCloudm_gridFilter
 Voxel grid filter.
COcPatchMaker m_patchMaker
 Patch maker.
tRegistrator m_registration
 Registration module.
tCloud::Ptr m_resampledCloud
 Cloud buffer.
tf::TransformListener m_tfListener
 Transform listener.

Detailed Description

Registrates incomming point cloud to the octomap

Definition at line 177 of file CPCtoOCRegistration.h.


Member Typedef Documentation

typedef sensor_msgs::PointCloud2 srs_env_model::CPcToOcRegistration::tCloud

Used cloud.

Definition at line 181 of file CPCtoOCRegistration.h.

Registration module type.

Definition at line 184 of file CPCtoOCRegistration.h.


Constructor & Destructor Documentation

Constructor.

Constructor

Definition at line 374 of file CPCtoOCRegistration.cpp.


Member Function Documentation

Get transform.

Definition at line 197 of file CPCtoOCRegistration.h.

void srs_env_model::CPcToOcRegistration::init ( ros::NodeHandle node_handle) [virtual]

Initialize plugin - called in server constructor.

Initialize plugin - called in server constructor

Definition at line 383 of file CPCtoOCRegistration.cpp.

Is some registering mode set.

Definition at line 200 of file CPCtoOCRegistration.h.

bool srs_env_model::CPcToOcRegistration::registerCloud ( tPointCloudPtr &  cloud,
const SMapWithParameters map 
)

Register cloud to the octomap.

Register cloud to the octomap

Definition at line 393 of file CPCtoOCRegistration.cpp.


Member Data Documentation

Voxel grid filter.

Definition at line 210 of file CPCtoOCRegistration.h.

Patch maker.

Definition at line 204 of file CPCtoOCRegistration.h.

Registration module.

Definition at line 207 of file CPCtoOCRegistration.h.

Cloud buffer.

Definition at line 213 of file CPCtoOCRegistration.h.

Transform listener.

Definition at line 216 of file CPCtoOCRegistration.h.


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


srs_env_model
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Tomas Lokaj, Jan Gorig, Michal Spanel (spanel@fit.vutbr.cz)
autogenerated on Sun Jan 5 2014 11:50:51