Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | List of all members
Receiver Class Reference

Public Types

enum  Mode { IMAGE = 0, CLOUD, BOTH }
 

Public Member Functions

 Receiver (const std::string &topicColor, const std::string &topicDepth, const bool useExact, const bool useCompressed)
 
void run (const Mode mode)
 
 ~Receiver ()
 

Private Types

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ApproximateSyncPolicy
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo > ExactSyncPolicy
 

Private Member Functions

void callback (const sensor_msgs::Image::ConstPtr imageColor, const sensor_msgs::Image::ConstPtr imageDepth, const sensor_msgs::CameraInfo::ConstPtr cameraInfoColor, const sensor_msgs::CameraInfo::ConstPtr cameraInfoDepth)
 
void cloudViewer ()
 
void combine (const cv::Mat &inC, const cv::Mat &inD, cv::Mat &out)
 
void createCloud (const cv::Mat &depth, const cv::Mat &color, pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &cloud) const
 
void createLookup (size_t width, size_t height)
 
void dispDepth (const cv::Mat &in, cv::Mat &out, const float maxValue)
 
void imageViewer ()
 
void keyboardEvent (const pcl::visualization::KeyboardEvent &event, void *)
 
void readCameraInfo (const sensor_msgs::CameraInfo::ConstPtr cameraInfo, cv::Mat &cameraMatrix) const
 
void readImage (const sensor_msgs::Image::ConstPtr msgImage, cv::Mat &image) const
 
void saveCloudAndImages (const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr cloud, const cv::Mat &color, const cv::Mat &depth, const cv::Mat &depthColored)
 
void start (const Mode mode)
 
void stop ()
 

Private Attributes

cv::Mat cameraMatrixColor
 
cv::Mat cameraMatrixDepth
 
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr cloud
 
cv::Mat color
 
cv::Mat depth
 
size_t frame
 
std::thread imageViewerThread
 
image_transport::ImageTransport it
 
std::mutex lock
 
cv::Mat lookupX
 
cv::Mat lookupY
 
Mode mode
 
ros::NodeHandle nh
 
std::ostringstream oss
 
std::vector< int > params
 
const size_t queueSize
 
bool running
 
bool save
 
ros::AsyncSpinner spinner
 
message_filters::Subscriber< sensor_msgs::CameraInfo > * subCameraInfoColor
 
message_filters::Subscriber< sensor_msgs::CameraInfo > * subCameraInfoDepth
 
image_transport::SubscriberFiltersubImageColor
 
image_transport::SubscriberFiltersubImageDepth
 
message_filters::Synchronizer< ApproximateSyncPolicy > * syncApproximate
 
message_filters::Synchronizer< ExactSyncPolicy > * syncExact
 
const std::string topicColor
 
const std::string topicDepth
 
bool updateCloud
 
bool updateImage
 
const bool useCompressed
 
const bool useExact
 
pcl::PCDWriter writer
 

Detailed Description

Copyright 2014 University of Bremen, Institute for Artificial Intelligence Author: Thiemo Wiedemeyer wiede.nosp@m.meye.nosp@m.r@cs..nosp@m.uni-.nosp@m.breme.nosp@m.n.de

Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at

http://www.apache.org/licenses/LICENSE-2.0

Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Definition at line 53 of file viewer.cpp.

Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> Receiver::ApproximateSyncPolicy
private

Definition at line 80 of file viewer.cpp.

typedef message_filters::sync_policies::ExactTime<sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> Receiver::ExactSyncPolicy
private

Definition at line 79 of file viewer.cpp.

Member Enumeration Documentation

Enumerator
IMAGE 
CLOUD 
BOTH 

Definition at line 56 of file viewer.cpp.

Constructor & Destructor Documentation

Receiver::Receiver ( const std::string &  topicColor,
const std::string &  topicDepth,
const bool  useExact,
const bool  useCompressed 
)
inline

Definition at line 100 of file viewer.cpp.

Receiver::~Receiver ( )
inline

Definition at line 116 of file viewer.cpp.

Member Function Documentation

void Receiver::callback ( const sensor_msgs::Image::ConstPtr  imageColor,
const sensor_msgs::Image::ConstPtr  imageDepth,
const sensor_msgs::CameraInfo::ConstPtr  cameraInfoColor,
const sensor_msgs::CameraInfo::ConstPtr  cameraInfoDepth 
)
inlineprivate

Definition at line 210 of file viewer.cpp.

void Receiver::cloudViewer ( )
inlineprivate

Definition at line 308 of file viewer.cpp.

void Receiver::combine ( const cv::Mat &  inC,
const cv::Mat &  inD,
cv::Mat &  out 
)
inlineprivate

Definition at line 412 of file viewer.cpp.

void Receiver::createCloud ( const cv::Mat &  depth,
const cv::Mat &  color,
pcl::PointCloud< pcl::PointXYZRGBA >::Ptr &  cloud 
) const
inlineprivate

Definition at line 433 of file viewer.cpp.

void Receiver::createLookup ( size_t  width,
size_t  height 
)
inlineprivate

Definition at line 490 of file viewer.cpp.

void Receiver::dispDepth ( const cv::Mat &  in,
cv::Mat &  out,
const float  maxValue 
)
inlineprivate

Definition at line 392 of file viewer.cpp.

void Receiver::imageViewer ( )
inlineprivate

Definition at line 236 of file viewer.cpp.

void Receiver::keyboardEvent ( const pcl::visualization::KeyboardEvent &  event,
void *   
)
inlineprivate

Definition at line 358 of file viewer.cpp.

void Receiver::readCameraInfo ( const sensor_msgs::CameraInfo::ConstPtr  cameraInfo,
cv::Mat &  cameraMatrix 
) const
inlineprivate

Definition at line 383 of file viewer.cpp.

void Receiver::readImage ( const sensor_msgs::Image::ConstPtr  msgImage,
cv::Mat &  image 
) const
inlineprivate

Definition at line 376 of file viewer.cpp.

void Receiver::run ( const Mode  mode)
inline

Definition at line 120 of file viewer.cpp.

void Receiver::saveCloudAndImages ( const pcl::PointCloud< pcl::PointXYZRGBA >::ConstPtr  cloud,
const cv::Mat &  color,
const cv::Mat &  depth,
const cv::Mat &  depthColored 
)
inlineprivate

Definition at line 468 of file viewer.cpp.

void Receiver::start ( const Mode  mode)
inlineprivate

Definition at line 127 of file viewer.cpp.

void Receiver::stop ( )
inlineprivate

Definition at line 185 of file viewer.cpp.

Member Data Documentation

cv::Mat Receiver::cameraMatrixColor
private

Definition at line 76 of file viewer.cpp.

cv::Mat Receiver::cameraMatrixDepth
private

Definition at line 76 of file viewer.cpp.

pcl::PointCloud<pcl::PointXYZRGBA>::Ptr Receiver::cloud
private

Definition at line 94 of file viewer.cpp.

cv::Mat Receiver::color
private

Definition at line 75 of file viewer.cpp.

cv::Mat Receiver::depth
private

Definition at line 75 of file viewer.cpp.

size_t Receiver::frame
private

Definition at line 72 of file viewer.cpp.

std::thread Receiver::imageViewerThread
private

Definition at line 91 of file viewer.cpp.

image_transport::ImageTransport Receiver::it
private

Definition at line 84 of file viewer.cpp.

std::mutex Receiver::lock
private

Definition at line 64 of file viewer.cpp.

cv::Mat Receiver::lookupX
private

Definition at line 77 of file viewer.cpp.

cv::Mat Receiver::lookupY
private

Definition at line 77 of file viewer.cpp.

Mode Receiver::mode
private

Definition at line 92 of file viewer.cpp.

ros::NodeHandle Receiver::nh
private

Definition at line 82 of file viewer.cpp.

std::ostringstream Receiver::oss
private

Definition at line 96 of file viewer.cpp.

std::vector<int> Receiver::params
private

Definition at line 97 of file viewer.cpp.

const size_t Receiver::queueSize
private

Definition at line 73 of file viewer.cpp.

bool Receiver::running
private

Definition at line 71 of file viewer.cpp.

bool Receiver::save
private

Definition at line 70 of file viewer.cpp.

ros::AsyncSpinner Receiver::spinner
private

Definition at line 83 of file viewer.cpp.

message_filters::Subscriber<sensor_msgs::CameraInfo>* Receiver::subCameraInfoColor
private

Definition at line 86 of file viewer.cpp.

message_filters::Subscriber<sensor_msgs::CameraInfo> * Receiver::subCameraInfoDepth
private

Definition at line 86 of file viewer.cpp.

image_transport::SubscriberFilter* Receiver::subImageColor
private

Definition at line 85 of file viewer.cpp.

image_transport::SubscriberFilter * Receiver::subImageDepth
private

Definition at line 85 of file viewer.cpp.

message_filters::Synchronizer<ApproximateSyncPolicy>* Receiver::syncApproximate
private

Definition at line 89 of file viewer.cpp.

message_filters::Synchronizer<ExactSyncPolicy>* Receiver::syncExact
private

Definition at line 88 of file viewer.cpp.

const std::string Receiver::topicColor
private

Definition at line 66 of file viewer.cpp.

const std::string Receiver::topicDepth
private

Definition at line 66 of file viewer.cpp.

bool Receiver::updateCloud
private

Definition at line 69 of file viewer.cpp.

bool Receiver::updateImage
private

Definition at line 69 of file viewer.cpp.

const bool Receiver::useCompressed
private

Definition at line 67 of file viewer.cpp.

const bool Receiver::useExact
private

Definition at line 67 of file viewer.cpp.

pcl::PCDWriter Receiver::writer
private

Definition at line 95 of file viewer.cpp.


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


kinect2_viewer
Author(s):
autogenerated on Wed Jan 3 2018 03:48:12