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

#include <compressed_pc_publisher.h>

List of all members.

Public Types

typedef
tInputData::_camera_info_type 
tCameraInfo
 Camera information type.
typedef
tInputData::_pointcloud2_type 
tInputCloudMsg
 Incoming point cloud type.
typedef
srs_env_model::OctomapUpdates 
tInputData
 Input data type.
typedef sensor_msgs::PointCloud2 tOutputCloudMsg
 Output point cloud message type.
typedef pcl::PointXYZRGB tPclPoint
 Define pcl point type.
typedef pcl::PointCloud
< tPclPoint
tPointCloudInternal
 Define internal point cloud type.

Public Member Functions

 CCompressedPCPublisher (ros::NodeHandle &nh)
 Constructor.

Protected Member Functions

long copyCloud (const tInputCloudMsg &input, tPointCloudInternal &output, bool bAdd=false)
 Copy point cloud from msg to internal type variable.
void incommingDataCB (const tInputData::ConstPtr &data)
 Input message cb.
bool inSensorCone (const cv::Point2d &uv) const
 Test if point is in sensor cone.
bool isRGBCloud (const tInputCloudMsg &cloud)
 Test if incomming pointcloud2 has rgb part.
long removeFrustumFromCloud (const tInputData::ConstPtr &data, tPointCloudInternal &cloud)
 Remove part of the cloud.

Protected Attributes

image_geometry::PinholeCameraModel m_camera_model
 Camera model.
cv::Size m_camera_size
 Camera size.
int m_camera_stereo_offset_left
 Camera offsets.
int m_camera_stereo_offset_right
std::string m_cameraFID
std::string m_cameraFrameId
 Camera frame id.
tPointCloudInternal m_cloud
 Stored point cloud.
ros::Publisher m_pub
 Publisher.
std::string m_publishedTopicName
 Published topic name.
std::string m_publishFID
 Publishing frame id.
message_filters::Subscriber
< tInputData
m_sub
 Subscriber.
std::string m_subscribedTopicName
 Subscribed topic name.
tf::MessageFilter< tInputData > * m_tf_filter
tf::TransformListener m_tfListener
 Transform listener.
tf::TransformListener m_tfListener2
tf::Transform m_to_pfid
 Transform from incomming pc to publishing frame id.
tf::Transform m_to_sensor
 Transform from pointcloud to camera space.

Detailed Description

publisher class

Definition at line 49 of file compressed_pc_publisher.h.


Member Typedef Documentation

typedef tInputData::_camera_info_type srs_env_model::CCompressedPCPublisher::tCameraInfo

Camera information type.

Definition at line 68 of file compressed_pc_publisher.h.

typedef tInputData::_pointcloud2_type srs_env_model::CCompressedPCPublisher::tInputCloudMsg

Incoming point cloud type.

Definition at line 62 of file compressed_pc_publisher.h.

typedef srs_env_model::OctomapUpdates srs_env_model::CCompressedPCPublisher::tInputData

Input data type.

Definition at line 59 of file compressed_pc_publisher.h.

Output point cloud message type.

Definition at line 65 of file compressed_pc_publisher.h.

Define pcl point type.

Definition at line 53 of file compressed_pc_publisher.h.

Define internal point cloud type.

Definition at line 56 of file compressed_pc_publisher.h.


Constructor & Destructor Documentation

Constructor.

Constructor

Definition at line 38 of file compressed_pc_publisher.cpp.


Member Function Documentation

long srs_env_model::CCompressedPCPublisher::copyCloud ( const tInputCloudMsg input,
tPointCloudInternal output,
bool  bAdd = false 
) [protected]

Copy point cloud from msg to internal type variable.

Copy point cloud from msg to internal type variable

Definition at line 159 of file compressed_pc_publisher.cpp.

void srs_env_model::CCompressedPCPublisher::incommingDataCB ( const tInputData::ConstPtr &  data) [protected]

Input message cb.

Input message cb

Definition at line 82 of file compressed_pc_publisher.cpp.

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

Test if point is in sensor cone.

Test if point is in camera cone

Definition at line 313 of file compressed_pc_publisher.cpp.

Test if incomming pointcloud2 has rgb part.

Test if incomming pointcloud2 has rgb part - parameter driven

Definition at line 215 of file compressed_pc_publisher.cpp.

long srs_env_model::CCompressedPCPublisher::removeFrustumFromCloud ( const tInputData::ConstPtr &  data,
tPointCloudInternal cloud 
) [protected]

Remove part of the cloud.

Remove part of the cloud

Definition at line 236 of file compressed_pc_publisher.cpp.


Member Data Documentation

Camera model.

Definition at line 118 of file compressed_pc_publisher.h.

Camera size.

Definition at line 112 of file compressed_pc_publisher.h.

Camera offsets.

Definition at line 109 of file compressed_pc_publisher.h.

Definition at line 109 of file compressed_pc_publisher.h.

Definition at line 127 of file compressed_pc_publisher.h.

Camera frame id.

Definition at line 115 of file compressed_pc_publisher.h.

Stored point cloud.

Definition at line 106 of file compressed_pc_publisher.h.

Publisher.

Definition at line 95 of file compressed_pc_publisher.h.

Published topic name.

Definition at line 92 of file compressed_pc_publisher.h.

Publishing frame id.

Definition at line 127 of file compressed_pc_publisher.h.

Subscriber.

Definition at line 102 of file compressed_pc_publisher.h.

Subscribed topic name.

Definition at line 98 of file compressed_pc_publisher.h.

Definition at line 103 of file compressed_pc_publisher.h.

Transform listener.

Definition at line 130 of file compressed_pc_publisher.h.

Definition at line 130 of file compressed_pc_publisher.h.

Transform from incomming pc to publishing frame id.

Definition at line 124 of file compressed_pc_publisher.h.

Transform from pointcloud to camera space.

Definition at line 121 of file compressed_pc_publisher.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