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

#include <point_cloud_plugin.h>

Inheritance diagram for srs_env_model::CPointCloudPlugin:
Inheritance graph
[legend]

List of all members.

Public Types

typedef sensor_msgs::PointCloud2 tIncommingPointCloud
 Incomming pointcloud type.

Public Member Functions

 CPointCloudPlugin (const std::string &name, bool subscribe)
 Constructor.
void enable (bool enabled)
 Enable or disable publishing.
virtual void init (ros::NodeHandle &node_handle)
 Initialize plugin - called in server constructor.
virtual void init (ros::NodeHandle &node_handle, bool subscribe)
 Initialize plugin - called in server constructor, enable or disable subscription.
virtual void init (ros::NodeHandle &node_handle, const std::string &topic)
 Initialize plugin - use given input topic name.
virtual void pause (bool bPause, ros::NodeHandle &node_handle)
 Pause/resume plugin. All publishers and subscribers are disconnected on pause.
void setDefaultColor (uint8_t r, uint8_t g, uint8_t b)
 Set default color value.
void setFrameSkip (unsigned long skip)
 Set frame skip.
void setUseInputColor (bool bUseInputColor)
 Set use input color switch value.
virtual bool wantsMap ()
 Wants plugin new map data?
virtual ~CPointCloudPlugin ()
 Destructor.

Protected Member Functions

void handleOccupiedNode (tButServerOcTree::iterator &it, const SMapWithParameters &mp)
 hook that is called when traversing occupied nodes of the updated Octree (does nothing here)
void insertCloudCallback (const tIncommingPointCloud::ConstPtr &cloud)
 Insert point cloud callback.
bool isRGBCloud (const tIncommingPointCloud::ConstPtr &cloud)
virtual void newMapDataCB (SMapWithParameters &par)
 Set used octomap frame id and timestamp.
virtual void publishInternal (const ros::Time &timestamp)
 Publish data implementation.
virtual bool shouldPublish ()
 Should plugin publish data?
virtual bool useFrame ()
 Counts frames and checks if node should publish in this frame.

Protected Attributes

long counter
 Counter.
uint8_t m_b
bool m_bAsInput
 Pointcloud working mode.
bool m_bFilterPC
 Do pointcloud filtering?
bool m_bSubscribe
 Should this plugin subscribe to some publishing topic?
tPointCloudPtr m_bufferCloud
 Used buffer cloud.
bool m_bUseInputColor
 Use input color information.
unsigned long m_frame_number
 Current frame number.
uint8_t m_g
std::string m_inputPcFrameId
 Input pointcloud frame id used to filter messages.
bool m_latchedTopics
tPointCloudPtr m_oldCloud
 Old point cloud used for registration.
Eigen::Matrix4f m_pcOutTM
 Output points transform matrix.
ros::Publisher m_pcPublisher
 Point cloud publisher.
std::string m_pcPublisherName
 Point cloud publisher name.
message_filters::Subscriber
< tIncommingPointCloud > * 
m_pcSubscriber
 Subscriber - point cloud.
std::string m_pcSubscriberName
 Point cloud subscriber name.
double m_pointcloudMaxZ
 Maximal Z value.
double m_pointcloudMinZ
 Minimal Z value.
bool m_publishPointCloud
 Is publishing enabled?
uint8_t m_r
 If not using input color use this.
tf::TransformListener m_tfListener
 Transform listener.
tf::MessageFilter
< tIncommingPointCloud > * 
m_tfPointCloudSub
 Message filter (we only want point cloud 2 messages)
unsigned long m_use_every_nth
 Use every n-th frame (if m_frame_number modulo m_use_every_nth)

Detailed Description

Definition at line 48 of file point_cloud_plugin.h.


Member Typedef Documentation

Incomming pointcloud type.

Definition at line 52 of file point_cloud_plugin.h.


Constructor & Destructor Documentation

srs_env_model::CPointCloudPlugin::CPointCloudPlugin ( const std::string &  name,
bool  subscribe 
)

Constructor.

Definition at line 42 of file point_cloud_plugin.cpp.

Destructor.

Definition at line 67 of file point_cloud_plugin.cpp.


Member Function Documentation

void srs_env_model::CPointCloudPlugin::enable ( bool  enabled) [inline]

Enable or disable publishing.

Definition at line 62 of file point_cloud_plugin.h.

void srs_env_model::CPointCloudPlugin::handleOccupiedNode ( tButServerOcTree::iterator &  it,
const SMapWithParameters mp 
) [protected]

hook that is called when traversing occupied nodes of the updated Octree (does nothing here)

Reimplemented in srs_env_model::CCompressedPointCloudPlugin, and srs_env_model::CLimitedPointCloudPlugin.

Definition at line 232 of file point_cloud_plugin.cpp.

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

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CServerPluginBase.

Reimplemented in srs_env_model::CCompressedPointCloudPlugin, and srs_env_model::CLimitedPointCloudPlugin.

Definition at line 73 of file point_cloud_plugin.cpp.

virtual void srs_env_model::CPointCloudPlugin::init ( ros::NodeHandle node_handle,
bool  subscribe 
) [inline, virtual]

Initialize plugin - called in server constructor, enable or disable subscription.

Definition at line 68 of file point_cloud_plugin.h.

virtual void srs_env_model::CPointCloudPlugin::init ( ros::NodeHandle node_handle,
const std::string &  topic 
) [inline, virtual]

Initialize plugin - use given input topic name.

Definition at line 71 of file point_cloud_plugin.h.

void srs_env_model::CPointCloudPlugin::insertCloudCallback ( const tIncommingPointCloud::ConstPtr &  cloud) [protected]

Insert point cloud callback.

Parameters:
cloudInput point cloud

Cloud insertion callback

Definition at line 264 of file point_cloud_plugin.cpp.

bool srs_env_model::CPointCloudPlugin::isRGBCloud ( const tIncommingPointCloud::ConstPtr &  cloud) [protected]

Test if incomming pointcloud2 has rgb part

Test if incomming pointcloud2 has rgb part - parameter driven

Definition at line 434 of file point_cloud_plugin.cpp.

void srs_env_model::CPointCloudPlugin::pause ( bool  bPause,
ros::NodeHandle node_handle 
) [virtual]

Pause/resume plugin. All publishers and subscribers are disconnected on pause.

Pause/resume plugin. All publishers and subscribers are disconnected on pause

Reimplemented from srs_env_model::CServerPluginBase.

Reimplemented in srs_env_model::CCompressedPointCloudPlugin, and srs_env_model::CLimitedPointCloudPlugin.

Definition at line 455 of file point_cloud_plugin.cpp.

void srs_env_model::CPointCloudPlugin::publishInternal ( const ros::Time timestamp) [protected, virtual]

Publish data implementation.

Called when new scan was inserted and now all can be published.

Implements srs_env_model::CServerPluginBase.

Reimplemented in srs_env_model::CCompressedPointCloudPlugin, and srs_env_model::CLimitedPointCloudPlugin.

Definition at line 143 of file point_cloud_plugin.cpp.

void srs_env_model::CPointCloudPlugin::setDefaultColor ( uint8_t  r,
uint8_t  g,
uint8_t  b 
) [inline]

Set default color value.

Definition at line 86 of file point_cloud_plugin.h.

void srs_env_model::CPointCloudPlugin::setFrameSkip ( unsigned long  skip) [inline]

Set frame skip.

Definition at line 80 of file point_cloud_plugin.h.

void srs_env_model::CPointCloudPlugin::setUseInputColor ( bool  bUseInputColor) [inline]

Set use input color switch value.

Definition at line 83 of file point_cloud_plugin.h.

Should plugin publish data?

Implements srs_env_model::CServerPluginBase.

Reimplemented in srs_env_model::CCompressedPointCloudPlugin.

Definition at line 426 of file point_cloud_plugin.cpp.

virtual bool srs_env_model::CPointCloudPlugin::useFrame ( ) [inline, protected, virtual]

Counts frames and checks if node should publish in this frame.

Definition at line 117 of file point_cloud_plugin.h.

Wants plugin new map data?

Reimplemented from srs_env_model::COctomapCrawlerBase< tButServerOcTree::NodeType >.

Reimplemented in srs_env_model::CLimitedPointCloudPlugin.

Definition at line 501 of file point_cloud_plugin.cpp.


Member Data Documentation

Counter.

Definition at line 160 of file point_cloud_plugin.h.

Definition at line 184 of file point_cloud_plugin.h.

Pointcloud working mode.

Definition at line 163 of file point_cloud_plugin.h.

Do pointcloud filtering?

Definition at line 151 of file point_cloud_plugin.h.

Should this plugin subscribe to some publishing topic?

Definition at line 142 of file point_cloud_plugin.h.

Used buffer cloud.

Definition at line 172 of file point_cloud_plugin.h.

Use input color information.

Definition at line 181 of file point_cloud_plugin.h.

Current frame number.

Definition at line 175 of file point_cloud_plugin.h.

Definition at line 184 of file point_cloud_plugin.h.

Input pointcloud frame id used to filter messages.

Definition at line 139 of file point_cloud_plugin.h.

Definition at line 148 of file point_cloud_plugin.h.

Old point cloud used for registration.

Definition at line 169 of file point_cloud_plugin.h.

Eigen::Matrix4f srs_env_model::CPointCloudPlugin::m_pcOutTM [protected]

Output points transform matrix.

Definition at line 166 of file point_cloud_plugin.h.

Point cloud publisher.

Definition at line 136 of file point_cloud_plugin.h.

Point cloud publisher name.

Definition at line 124 of file point_cloud_plugin.h.

Subscriber - point cloud.

Definition at line 130 of file point_cloud_plugin.h.

Point cloud subscriber name.

Definition at line 127 of file point_cloud_plugin.h.

Maximal Z value.

Definition at line 157 of file point_cloud_plugin.h.

Minimal Z value.

Definition at line 154 of file point_cloud_plugin.h.

Is publishing enabled?

Definition at line 121 of file point_cloud_plugin.h.

If not using input color use this.

Definition at line 184 of file point_cloud_plugin.h.

Transform listener.

Reimplemented in srs_env_model::CCompressedPointCloudPlugin.

Definition at line 145 of file point_cloud_plugin.h.

Message filter (we only want point cloud 2 messages)

Definition at line 133 of file point_cloud_plugin.h.

Use every n-th frame (if m_frame_number modulo m_use_every_nth)

Definition at line 178 of file point_cloud_plugin.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