Public Member Functions | Protected Member Functions | Protected Attributes
srs_env_model::CLimitedPointCloudPlugin Class Reference

#include <limited_point_cloud_plugin.h>

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

List of all members.

Public Member Functions

 CLimitedPointCloudPlugin (const std::string &name)
 Constructor.
virtual void init (ros::NodeHandle &node_handle)
 Initialize plugin - called in server constructor.
virtual void pause (bool bPause, ros::NodeHandle &node_handle)
 Connect/disconnect plugin to/from all topics.
virtual bool wantsMap ()
 Wants plugin new map data?
virtual ~CLimitedPointCloudPlugin ()
 Destructor.

Protected Member Functions

virtual void handleOccupiedNode (tButServerOcTree::iterator &it, const SMapWithParameters &mp)
 hook that is called when traversing occupied nodes of the updated Octree (does nothing here)
virtual void newMapDataCB (SMapWithParameters &par)
 Set used octomap frame id and timestamp.
void onCameraPositionChangedCB (const srs_env_model_msgs::RVIZCameraPosition::ConstPtr &position)
 On camera position changed callback.
virtual void publishInternal (const ros::Time &timestamp)
 Called when new scan was inserted and now all can be published.
void spinThread ()

Protected Attributes

ros::CallbackQueue callback_queue_
bool m_bSpinThread
 Spin out own input callback thread.
bool m_bTransformCamera
 Should camera position and orientation be transformed?
std::string m_cameraFrameId
 Camera frame id.
std::string m_cameraPositionTopic
boost::recursive_mutex m_camPosMutex
ros::Subscriber m_camPosSubscriber
 Subscriber - camera position.
Eigen::Matrix3f m_camToOcRot
 Transformation from camera to the octomap frame id - rotation.
Eigen::Vector3f m_camToOcTrans
 Transformation from camera to the octomap frame id - translation.
long m_countHidden
long m_countVisible
 Counters.
float m_d
 Last part of the plane equation.
float m_dBuf
Eigen::Vector3f m_normal
 Camera normalized normal - part of the plane equation.
Eigen::Vector3f m_normalBuf
tf::MessageFilter
< srs_env_model_msgs::RVIZCameraPosition > * 
m_tfCamPosSub
 Message filter (we only want point cloud 2 messages)
float max
float min
volatile bool need_to_terminate_
ros::NodeHandle node_handle_
boost::scoped_ptr< boost::thread > spin_thread_

Detailed Description

Definition at line 43 of file limited_point_cloud_plugin.h.


Constructor & Destructor Documentation

Constructor.

Constructor

Definition at line 37 of file limited_point_cloud_plugin.cpp.

Destructor.

Destructor - kill thread

Definition at line 47 of file limited_point_cloud_plugin.cpp.


Member Function Documentation

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

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

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 223 of file limited_point_cloud_plugin.cpp.

Initialize plugin - called in server constructor.

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 71 of file limited_point_cloud_plugin.cpp.

Set used octomap frame id and timestamp.

Set used octomap frame id and timestamp

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 118 of file limited_point_cloud_plugin.cpp.

On camera position changed callback.

On camera position changed callback

Definition at line 250 of file limited_point_cloud_plugin.cpp.

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

Connect/disconnect plugin to/from all topics.

Connect/disconnect plugin to/from all topics

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 302 of file limited_point_cloud_plugin.cpp.

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

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

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 292 of file limited_point_cloud_plugin.cpp.

Thread body - call callbacks, if needed

Definition at line 59 of file limited_point_cloud_plugin.cpp.

Wants plugin new map data?

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 59 of file limited_point_cloud_plugin.h.


Member Data Documentation

Definition at line 122 of file limited_point_cloud_plugin.h.

Spin out own input callback thread.

Definition at line 117 of file limited_point_cloud_plugin.h.

Should camera position and orientation be transformed?

Definition at line 84 of file limited_point_cloud_plugin.h.

Camera frame id.

Definition at line 87 of file limited_point_cloud_plugin.h.

Definition at line 90 of file limited_point_cloud_plugin.h.

boost::recursive_mutex srs_env_model::CLimitedPointCloudPlugin::m_camPosMutex [protected]

Definition at line 126 of file limited_point_cloud_plugin.h.

Subscriber - camera position.

Definition at line 106 of file limited_point_cloud_plugin.h.

Transformation from camera to the octomap frame id - rotation.

Definition at line 99 of file limited_point_cloud_plugin.h.

Transformation from camera to the octomap frame id - translation.

Definition at line 102 of file limited_point_cloud_plugin.h.

Definition at line 112 of file limited_point_cloud_plugin.h.

Counters.

Definition at line 112 of file limited_point_cloud_plugin.h.

Last part of the plane equation.

Definition at line 96 of file limited_point_cloud_plugin.h.

Definition at line 96 of file limited_point_cloud_plugin.h.

Camera normalized normal - part of the plane equation.

Definition at line 93 of file limited_point_cloud_plugin.h.

Definition at line 93 of file limited_point_cloud_plugin.h.

Message filter (we only want point cloud 2 messages)

Definition at line 109 of file limited_point_cloud_plugin.h.

Definition at line 114 of file limited_point_cloud_plugin.h.

Definition at line 114 of file limited_point_cloud_plugin.h.

Definition at line 123 of file limited_point_cloud_plugin.h.

Definition at line 121 of file limited_point_cloud_plugin.h.

boost::scoped_ptr<boost::thread> srs_env_model::CLimitedPointCloudPlugin::spin_thread_ [protected]

Definition at line 120 of file limited_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:50