Handles most of the ROS-based communication. More...
#include <openni_listener.h>
Public Slots | |
void | getOneFrame () |
Process a single incomming frame. Useful in pause-mode for getting one snapshot at a time. | |
void | toggleBagRecording () |
void | togglePause () |
Switch between processing or ignoring new incoming data. | |
Signals | |
void | bagFinished () |
void | newDepthImage (QImage) |
Connect to this signal to get up-to-date depth images from the listener. | |
void | newFeatureFlowImage (QImage) |
Connect to this signal to get up-to-date featureFlow visualizations from the listener. | |
void | newTransformationMatrix (QString) |
Connect to this signal to get the transformation matrix from the last frame as QString. | |
void | newVisualImage (QImage) |
QT Stuff, to communicate with the gui. | |
void | setGUIInfo (QString message) |
Set the info label on the right side in the statusbar of the GUI. | |
void | setGUIStatus (QString message) |
Set the temporary status-message in the GUI. | |
Public Member Functions | |
void | kinectCallback (const sensor_msgs::ImageConstPtr &visual_img, const sensor_msgs::ImageConstPtr &depth_img, const sensor_msgs::PointCloud2ConstPtr &point_cloud) |
Listen to kinect data, construct nodes and feed the graph manager with it. | |
void | loadBag (const std::string &filename) |
Load data from bag file. | |
void | noCloudCallback (const sensor_msgs::ImageConstPtr &visual_img_msg, const sensor_msgs::ImageConstPtr &depth_img_msg, const sensor_msgs::CameraInfoConstPtr &cam_info_msg) |
For this callback the point cloud is not required. | |
OpenNIListener (ros::NodeHandle nh, GraphManager *g_mgr) | |
Ctor: setup synced listening to ros topics (kinect/stereo data) and prepare the feature handling. | |
void | stereoCallback (const sensor_msgs::ImageConstPtr &visual_img_msg, const sensor_msgs::PointCloud2ConstPtr &point_cloud) |
No depth image but pointcloud, e.g., for stereo cameras. | |
~OpenNIListener () | |
Delete tflistener, shutdown ros publishers. | |
Protected Member Functions | |
void | callProcessing (cv::Mat gray_img, Node *node_ptr) |
Call processNode either regularly or as background thread. | |
void | cameraCallback (cv::Mat visual_img, pointcloud_type::Ptr point_cloud, cv::Mat depth_mono8_img) |
common processing | |
QImage | cvMat2QImage (const cv::Mat &image, unsigned int idx) |
Create a QImage from image. The QImage stores its data in the rgba_buffers_ indexed by idx (reused/overwritten each call) | |
QImage | cvMat2QImage (const cv::Mat &channel1, const cv::Mat &channel2, const cv::Mat &channel3, unsigned int idx) |
Create a QImage from image. The QImage stores its data in the rgba_buffers_ indexed by idx (reused/overwritten each call) | |
void | noCloudCameraCallback (cv::Mat visual_img, cv::Mat depth, cv::Mat depth_mono8_img, std_msgs::Header depth_header, const sensor_msgs::CameraInfoConstPtr &cam_info) |
as cameraCallback, but create Node without cloud | |
void | processNode (Node *new_node) |
processNode is called by cameraCallback in a separate thread and after finishing visualizes the results | |
void | retrieveTransformations (std_msgs::Header depth_header, Node *node_ptr) |
Retrieve the transform between the lens and the base-link at capturing time. | |
Protected Attributes | |
rosbag::Bag | bag |
QMutex | bagfile_mutex |
BagSubscriber < sensor_msgs::CameraInfo > * | cam_info_sub_ |
message_filters::Subscriber < sensor_msgs::CameraInfo > * | cinfo_sub_ |
message_filters::Subscriber < sensor_msgs::PointCloud2 > * | cloud_sub_ |
int | data_id_ |
BagSubscriber < sensor_msgs::Image > * | depth_img_sub_ |
cv::Mat | depth_mono8_img_ |
message_filters::Subscriber < sensor_msgs::Image > * | depth_sub_ |
cv::Ptr< cv::FeatureDetector > | detector_ |
cv::Ptr< cv::DescriptorExtractor > | extractor_ |
bool | first_frame_ |
QFuture< void > | future_ |
bool | getOneFrame_ |
GraphManager * | graph_mgr_ |
std::string | image_encoding_ |
message_filters::Synchronizer < KinectSyncPolicy > * | kinect_sync_ |
message_filters::Synchronizer < NoCloudSyncPolicy > * | no_cloud_sync_ |
bool | pause_ |
BagSubscriber < sensor_msgs::Image > * | rgb_img_sub_ |
std::vector< cv::Mat > | rgba_buffers_ |
bool | save_bag_file |
message_filters::Synchronizer < StereoSyncPolicy > * | stereo_sync_ |
tf::TransformBroadcaster | tf_br_ |
this being a pointer saves the include (using the above forward declaration) | |
ros::Publisher | tf_pub_ |
tf::TransformListener * | tflistener_ |
message_filters::Subscriber < sensor_msgs::Image > * | visua_sub_ |
cv::Mat | visualization_depth_mono8_img_ |
The depth mono img is stored here for visualization purposes. | |
cv::Mat | visualization_img_ |
The visual img is stored here for visualization purposes here. |
Handles most of the ROS-based communication.
The purpose of this class is to listen to synchronized image pairs from the kinect convert them to opencv, process them, convert them to a qt image and send them to the mainwindow defined in qtcv.h/.cpp
Definition at line 77 of file openni_listener.h.
OpenNIListener::OpenNIListener | ( | ros::NodeHandle | nh, |
GraphManager * | g_mgr | ||
) |
Ctor: setup synced listening to ros topics (kinect/stereo data) and prepare the feature handling.
Constructor: The listener needs to know the node handle and the GraphManager instance. Which topics to listen to and which feature detector/extractor to use is queried from the parameter server.
Definition at line 55 of file openni_listener.cpp.
Delete tflistener, shutdown ros publishers.
Definition at line 342 of file openni_listener.cpp.
void OpenNIListener::bagFinished | ( | ) | [signal] |
void OpenNIListener::callProcessing | ( | cv::Mat | gray_img, |
Node * | node_ptr | ||
) | [protected] |
Call processNode either regularly or as background thread.
Definition at line 546 of file openni_listener.cpp.
void OpenNIListener::cameraCallback | ( | cv::Mat | visual_img, |
pointcloud_type::Ptr | point_cloud, | ||
cv::Mat | depth_mono8_img | ||
) | [protected] |
common processing
Definition at line 489 of file openni_listener.cpp.
QImage OpenNIListener::cvMat2QImage | ( | const cv::Mat & | image, |
unsigned int | idx | ||
) | [protected] |
Create a QImage from image. The QImage stores its data in the rgba_buffers_ indexed by idx (reused/overwritten each call)
Create a QImage from one image. The QImage stores its data in the rgba_buffers_ indexed by idx (reused/overwritten each call)
Definition at line 674 of file openni_listener.cpp.
QImage OpenNIListener::cvMat2QImage | ( | const cv::Mat & | channel1, |
const cv::Mat & | channel2, | ||
const cv::Mat & | channel3, | ||
unsigned int | idx | ||
) | [protected] |
Create a QImage from image. The QImage stores its data in the rgba_buffers_ indexed by idx (reused/overwritten each call)
Create a QImage from several one-channel images. The QImage stores its data in the rgba_buffers_ indexed by idx (reused/overwritten each call)
Definition at line 642 of file openni_listener.cpp.
void OpenNIListener::getOneFrame | ( | ) | [slot] |
Process a single incomming frame. Useful in pause-mode for getting one snapshot at a time.
Definition at line 638 of file openni_listener.cpp.
void OpenNIListener::kinectCallback | ( | const sensor_msgs::ImageConstPtr & | visual_img, |
const sensor_msgs::ImageConstPtr & | depth_img, | ||
const sensor_msgs::PointCloud2ConstPtr & | point_cloud | ||
) |
Listen to kinect data, construct nodes and feed the graph manager with it.
For each dataset from the kinect, do some data conversion, construct a node, hand it to the graph manager and do some visualization of the result in the GUI and RVIZ.
Definition at line 435 of file openni_listener.cpp.
void OpenNIListener::loadBag | ( | const std::string & | filename | ) |
Load data from bag file.
This function reads the sensor input from a bagfile specified in the parameter bagfile_name. It is meant for offline processing of each frame
Definition at line 152 of file openni_listener.cpp.
void OpenNIListener::newDepthImage | ( | QImage | ) | [signal] |
Connect to this signal to get up-to-date depth images from the listener.
void OpenNIListener::newFeatureFlowImage | ( | QImage | ) | [signal] |
Connect to this signal to get up-to-date featureFlow visualizations from the listener.
void OpenNIListener::newTransformationMatrix | ( | QString | ) | [signal] |
Connect to this signal to get the transformation matrix from the last frame as QString.
void OpenNIListener::newVisualImage | ( | QImage | ) | [signal] |
QT Stuff, to communicate with the gui.
Connect to this signal to get up-to-date optical images from the listener
void OpenNIListener::noCloudCallback | ( | const sensor_msgs::ImageConstPtr & | visual_img_msg, |
const sensor_msgs::ImageConstPtr & | depth_img_msg, | ||
const sensor_msgs::CameraInfoConstPtr & | cam_info_msg | ||
) |
For this callback the point cloud is not required.
Definition at line 346 of file openni_listener.cpp.
void OpenNIListener::noCloudCameraCallback | ( | cv::Mat | visual_img, |
cv::Mat | depth, | ||
cv::Mat | depth_mono8_img, | ||
std_msgs::Header | depth_header, | ||
const sensor_msgs::CameraInfoConstPtr & | cam_info | ||
) | [protected] |
as cameraCallback, but create Node without cloud
Definition at line 516 of file openni_listener.cpp.
void OpenNIListener::processNode | ( | Node * | new_node | ) | [protected] |
processNode is called by cameraCallback in a separate thread and after finishing visualizes the results
Definition at line 575 of file openni_listener.cpp.
void OpenNIListener::retrieveTransformations | ( | std_msgs::Header | depth_header, |
Node * | node_ptr | ||
) | [protected] |
Retrieve the transform between the lens and the base-link at capturing time.
Definition at line 707 of file openni_listener.cpp.
void OpenNIListener::setGUIInfo | ( | QString | message | ) | [signal] |
Set the info label on the right side in the statusbar of the GUI.
void OpenNIListener::setGUIStatus | ( | QString | message | ) | [signal] |
Set the temporary status-message in the GUI.
void OpenNIListener::stereoCallback | ( | const sensor_msgs::ImageConstPtr & | visual_img_msg, |
const sensor_msgs::PointCloud2ConstPtr & | point_cloud | ||
) |
No depth image but pointcloud, e.g., for stereo cameras.
Definition at line 286 of file openni_listener.cpp.
void OpenNIListener::toggleBagRecording | ( | ) | [slot] |
Definition at line 608 of file openni_listener.cpp.
void OpenNIListener::togglePause | ( | ) | [slot] |
Switch between processing or ignoring new incoming data.
Definition at line 632 of file openni_listener.cpp.
rosbag::Bag OpenNIListener::bag [protected] |
Definition at line 181 of file openni_listener.h.
QMutex OpenNIListener::bagfile_mutex [protected] |
Definition at line 190 of file openni_listener.h.
BagSubscriber<sensor_msgs::CameraInfo>* OpenNIListener::cam_info_sub_ [protected] |
Definition at line 172 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::CameraInfo>* OpenNIListener::cinfo_sub_ [protected] |
Definition at line 167 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::PointCloud2>* OpenNIListener::cloud_sub_ [protected] |
Definition at line 168 of file openni_listener.h.
int OpenNIListener::data_id_ [protected] |
Definition at line 194 of file openni_listener.h.
BagSubscriber<sensor_msgs::Image>* OpenNIListener::depth_img_sub_ [protected] |
Definition at line 171 of file openni_listener.h.
cv::Mat OpenNIListener::depth_mono8_img_ [protected] |
Definition at line 174 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::Image>* OpenNIListener::depth_sub_ [protected] |
Definition at line 166 of file openni_listener.h.
cv::Ptr<cv::FeatureDetector> OpenNIListener::detector_ [protected] |
Definition at line 159 of file openni_listener.h.
cv::Ptr<cv::DescriptorExtractor> OpenNIListener::extractor_ [protected] |
Definition at line 160 of file openni_listener.h.
bool OpenNIListener::first_frame_ [protected] |
Definition at line 188 of file openni_listener.h.
QFuture<void> OpenNIListener::future_ [protected] |
Definition at line 189 of file openni_listener.h.
bool OpenNIListener::getOneFrame_ [protected] |
Definition at line 187 of file openni_listener.h.
GraphManager* OpenNIListener::graph_mgr_ [protected] |
The GraphManager uses the Node objects to do the actual SLAM Public, s.t. the qt signals can be connected to by the holder of the OpenNIListener
Definition at line 156 of file openni_listener.h.
std::string OpenNIListener::image_encoding_ [protected] |
Definition at line 195 of file openni_listener.h.
Definition at line 163 of file openni_listener.h.
Definition at line 164 of file openni_listener.h.
bool OpenNIListener::pause_ [protected] |
Definition at line 186 of file openni_listener.h.
BagSubscriber<sensor_msgs::Image>* OpenNIListener::rgb_img_sub_ [protected] |
Definition at line 170 of file openni_listener.h.
std::vector<cv::Mat> OpenNIListener::rgba_buffers_ [protected] |
Definition at line 179 of file openni_listener.h.
bool OpenNIListener::save_bag_file [protected] |
Definition at line 182 of file openni_listener.h.
Definition at line 162 of file openni_listener.h.
tf::TransformBroadcaster OpenNIListener::tf_br_ [protected] |
this being a pointer saves the include (using the above forward declaration)
Definition at line 192 of file openni_listener.h.
ros::Publisher OpenNIListener::tf_pub_ [protected] |
Definition at line 193 of file openni_listener.h.
tf::TransformListener* OpenNIListener::tflistener_ [protected] |
Definition at line 191 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::Image>* OpenNIListener::visua_sub_ [protected] |
Definition at line 165 of file openni_listener.h.
cv::Mat OpenNIListener::visualization_depth_mono8_img_ [protected] |
The depth mono img is stored here for visualization purposes.
Definition at line 176 of file openni_listener.h.
cv::Mat OpenNIListener::visualization_img_ [protected] |
The visual img is stored here for visualization purposes here.
Definition at line 178 of file openni_listener.h.