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

#include <compressed_point_cloud_plugin.h>

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

List of all members.

Public Member Functions

 CCompressedPointCloudPlugin (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 ~CCompressedPointCloudPlugin ()
 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)
bool inSensorCone (const cv::Point2d &uv) const
 Test if point is in camera cone.
virtual void newMapDataCB (SMapWithParameters &par)
 Set used octomap frame id and timestamp.
void onCameraChangedCB (const sensor_msgs::CameraInfo::ConstPtr &cam_info)
 On camera position changed callback.
void publishInternal (const ros::Time &timestamp)
 Called when new scan was inserted and now all can be published.
bool setNumIncompleteFramesCB (srs_env_model::SetNumIncompleteFrames::Request &req, srs_env_model::SetNumIncompleteFrames::Response &res)
 Set number of incomplete frames callback.
virtual bool shouldPublish ()
 Should plugin publish data?
void spinThread ()

Protected Attributes

ros::CallbackQueue callback_queue_
bool m_bCamModelInitialized
 Is camera model initialized?
bool m_bCreatePackedInfoMsg
 Create packed info message?
bool m_bPublishComplete
 Should be complete frame published?
bool m_bPublishSimpleCloud
 Publish simple cloud too?
bool m_bSpinThread
 Spin out own input callback thread.
bool m_bTransformCamera
 Should camera position and orientation be transformed?
bool m_bTransformOutput
 Should output pointcloud be transformed.
sensor_msgs::CameraInfo m_camera_info_buffer
 Camera info buffer.
image_geometry::PinholeCameraModel m_camera_model
 Camera model.
image_geometry::PinholeCameraModel m_camera_model_buffer
cv::Size m_camera_size
 Camera size.
cv::Size m_camera_size_buffer
int m_camera_stereo_offset_left
 Camera offsets.
int m_camera_stereo_offset_right
std::string m_cameraFrameId
 Camera frame id.
std::string m_cameraInfoTopic
boost::recursive_mutex m_camPosMutex
ros::Subscriber m_camPosSubscriber
 Subscriber - camera position.
long m_countAll
long m_countVisible
 Counters.
long m_frame_counter
 Pubilishing counter.
srs_env_model::OctomapUpdatesPtr m_octomap_updates_msg
 Packed info message data.
ros::Publisher m_ocUpdatePublisher
 Publisher - packed info.
std::string m_ocUpdatePublisherName
 Packed info publisher name.
ros::ServiceServer m_serviceSetNumIncomplete
 Service - set number of incomplete frames.
tf::MessageFilter
< srs_env_model_msgs::RVIZCameraPosition > * 
m_tfCamPosSub
 Message filter (we only want point cloud 2 messages)
tf::TransformListener m_tfListener
 Transform listener.
tf::Transform m_to_sensor
 Transform from pointcloud to camera space.
long m_uncomplete_frames
 Every n-th frame should be complete.
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 46 of file compressed_point_cloud_plugin.h.


Constructor & Destructor Documentation

Constructor.

Constructor

Definition at line 37 of file compressed_point_cloud_plugin.cpp.

Destructor.

Destructor - kill thread

Definition at line 53 of file compressed_point_cloud_plugin.cpp.


Member Function Documentation

void srs_env_model::CCompressedPointCloudPlugin::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 280 of file compressed_point_cloud_plugin.cpp.

Initialize plugin - called in server constructor.

Initialize plugin

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 80 of file compressed_point_cloud_plugin.cpp.

bool srs_env_model::CCompressedPointCloudPlugin::inSensorCone ( const cv::Point2d &  uv) const [protected]

Test if point is in camera cone.

Test if point is in camera cone

Definition at line 403 of file compressed_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 163 of file compressed_point_cloud_plugin.cpp.

void srs_env_model::CCompressedPointCloudPlugin::onCameraChangedCB ( const sensor_msgs::CameraInfo::ConstPtr &  cam_info) [protected]

On camera position changed callback.

On camera position changed callback

Definition at line 309 of file compressed_point_cloud_plugin.cpp.

void srs_env_model::CCompressedPointCloudPlugin::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 380 of file compressed_point_cloud_plugin.cpp.

void srs_env_model::CCompressedPointCloudPlugin::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 331 of file compressed_point_cloud_plugin.cpp.

bool srs_env_model::CCompressedPointCloudPlugin::setNumIncompleteFramesCB ( srs_env_model::SetNumIncompleteFrames::Request &  req,
srs_env_model::SetNumIncompleteFrames::Response &  res 
) [protected]

Set number of incomplete frames callback.

Set number of incomplete frames callback

Definition at line 437 of file compressed_point_cloud_plugin.cpp.

Should plugin publish data?

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 420 of file compressed_point_cloud_plugin.cpp.

Thread body - call callbacks, if needed

Definition at line 65 of file compressed_point_cloud_plugin.cpp.


Member Data Documentation

Definition at line 127 of file compressed_point_cloud_plugin.h.

Is camera model initialized?

Definition at line 152 of file compressed_point_cloud_plugin.h.

Create packed info message?

Definition at line 164 of file compressed_point_cloud_plugin.h.

Should be complete frame published?

Definition at line 161 of file compressed_point_cloud_plugin.h.

Publish simple cloud too?

Definition at line 167 of file compressed_point_cloud_plugin.h.

Spin out own input callback thread.

Definition at line 122 of file compressed_point_cloud_plugin.h.

Should camera position and orientation be transformed?

Definition at line 94 of file compressed_point_cloud_plugin.h.

Should output pointcloud be transformed.

Definition at line 176 of file compressed_point_cloud_plugin.h.

Camera info buffer.

Definition at line 149 of file compressed_point_cloud_plugin.h.

Camera model.

Definition at line 134 of file compressed_point_cloud_plugin.h.

Definition at line 134 of file compressed_point_cloud_plugin.h.

Camera size.

Definition at line 146 of file compressed_point_cloud_plugin.h.

Definition at line 146 of file compressed_point_cloud_plugin.h.

Camera offsets.

Definition at line 143 of file compressed_point_cloud_plugin.h.

Definition at line 143 of file compressed_point_cloud_plugin.h.

Camera frame id.

Definition at line 97 of file compressed_point_cloud_plugin.h.

Definition at line 100 of file compressed_point_cloud_plugin.h.

Definition at line 131 of file compressed_point_cloud_plugin.h.

Subscriber - camera position.

Definition at line 105 of file compressed_point_cloud_plugin.h.

Definition at line 117 of file compressed_point_cloud_plugin.h.

Counters.

Definition at line 117 of file compressed_point_cloud_plugin.h.

Pubilishing counter.

Definition at line 155 of file compressed_point_cloud_plugin.h.

srs_env_model::OctomapUpdatesPtr srs_env_model::CCompressedPointCloudPlugin::m_octomap_updates_msg [protected]

Packed info message data.

Definition at line 170 of file compressed_point_cloud_plugin.h.

Publisher - packed info.

Definition at line 108 of file compressed_point_cloud_plugin.h.

Packed info publisher name.

Definition at line 111 of file compressed_point_cloud_plugin.h.

Service - set number of incomplete frames.

Definition at line 173 of file compressed_point_cloud_plugin.h.

Message filter (we only want point cloud 2 messages)

Definition at line 114 of file compressed_point_cloud_plugin.h.

Transform listener.

Reimplemented from srs_env_model::CPointCloudPlugin.

Definition at line 137 of file compressed_point_cloud_plugin.h.

Transform from pointcloud to camera space.

Definition at line 140 of file compressed_point_cloud_plugin.h.

Every n-th frame should be complete.

Definition at line 158 of file compressed_point_cloud_plugin.h.

Definition at line 119 of file compressed_point_cloud_plugin.h.

Definition at line 119 of file compressed_point_cloud_plugin.h.

Definition at line 128 of file compressed_point_cloud_plugin.h.

Definition at line 126 of file compressed_point_cloud_plugin.h.

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

Definition at line 125 of file compressed_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