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 | loadBagFileFromGUI (QString) |
void | loadPCDFiles (QStringList) |
void | togglePause () |
Switch between processing or ignoring new incoming data. | |
Signals | |
void | bagFinished () |
void | iamBusy (int id, const char *message, int max) |
void | newDepthImage (QImage) |
Connect to this signal to get up-to-date depth images from the listener. | |
void | newFeatureFlowImage (QImage) |
void | newFeatureImage (QImage) |
Connect to this signal to get up-to-date featureFlow visualizations from the listener. | |
void | newVisualImage (QImage) |
QT Stuff, to communicate with the gui. | |
void | progress (int id, const char *message, int val) |
void | setGUIInfo (QString message) |
Set the info label on the right side in the statusbar of the GUI. | |
void | setGUIInfo2 (QString message) |
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 | 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. | |
void | odomCallback (const nav_msgs::OdometryConstPtr &odom_msg) |
Callback for the robot odometry. | |
OpenNIListener (GraphManager *g_mgr) | |
Ctor: setup synced listening to ros topics (kinect/stereo data) and prepare the feature handling. | |
void | pcdCallback (const sensor_msgs::ImageConstPtr visual_img_msg, pointcloud_type::Ptr point_cloud) |
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 | evaluation (std::string filename) |
Perform scientific evaluations and write according logs. | |
void | loadBag (std::string filename) |
Loads a bagfile and processes every rgb-d frame pair. | |
void | loadBagFakeSubscriberSetup (const std::string &visua_tpc, const std::string &depth_tpc, const std::string &points_tpc, const std::string &cinfo_tpc, const std::string &odom_tpc, const std::string &tf_tpc) |
Setup the ROS Subscribers for loadbag. | |
void | loadPCDFilesAsync (QStringList) |
Load files in Background to not deadlock. | |
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 | processBagfile (std::string filename, const std::string &visua_tpc, const std::string &depth_tpc, const std::string &points_tpc, const std::string &cinfo_tpc, const std::string &odom_tpc, const std::string &tf_tpc) |
processing the bagfile for loadBag | |
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. | |
void | setupSubscribers () |
Setup subscriber callbacks according to the topic parameters. | |
void | visualize_images (cv::Mat visual_image, cv::Mat depth_image) |
void | waitAndEvaluate (const std::string &filename) |
delay after processing and trigger scientific evaluation | |
Protected Attributes | |
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_ |
int | num_processed_ |
message_filters::Subscriber < nav_msgs::Odometry > * | odom_sub_ |
bool | pause_ |
BagSubscriber < sensor_msgs::PointCloud2 > * | pc_sub_ |
BagSubscriber < sensor_msgs::Image > * | rgb_img_sub_ |
std::vector< cv::Mat > | rgba_buffers_ |
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 79 of file openni_listener.h.
OpenNIListener::OpenNIListener | ( | 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 114 of file openni_listener.cpp.
Delete tflistener, shutdown ros publishers.
Definition at line 595 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 787 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 742 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 912 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 877 of file openni_listener.cpp.
void OpenNIListener::evaluation | ( | std::string | filename | ) | [protected] |
Perform scientific evaluations and write according logs.
Definition at line 430 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 871 of file openni_listener.cpp.
void OpenNIListener::iamBusy | ( | int | id, |
const char * | message, | ||
int | max | ||
) | [signal] |
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 675 of file openni_listener.cpp.
void OpenNIListener::loadBag | ( | std::string | filename | ) | [protected] |
Loads a bagfile and processes every rgb-d frame pair.
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 387 of file openni_listener.cpp.
void OpenNIListener::loadBagFakeSubscriberSetup | ( | const std::string & | visua_tpc, |
const std::string & | depth_tpc, | ||
const std::string & | points_tpc, | ||
const std::string & | cinfo_tpc, | ||
const std::string & | odom_tpc, | ||
const std::string & | tf_tpc | ||
) | [protected] |
Setup the ROS Subscribers for loadbag.
Definition at line 341 of file openni_listener.cpp.
void OpenNIListener::loadBagFileFromGUI | ( | QString | file | ) | [slot] |
Definition at line 1111 of file openni_listener.cpp.
void OpenNIListener::loadPCDFiles | ( | QStringList | file_list | ) | [slot] |
Definition at line 1062 of file openni_listener.cpp.
void OpenNIListener::loadPCDFilesAsync | ( | QStringList | file_list | ) | [protected] |
Load files in Background to not deadlock.
Definition at line 1067 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] |
void OpenNIListener::newFeatureImage | ( | QImage | ) | [signal] |
Connect to this signal to get up-to-date featureFlow visualizations from the listener.
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 599 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 764 of file openni_listener.cpp.
void OpenNIListener::odomCallback | ( | const nav_msgs::OdometryConstPtr & | odom_msg | ) |
Callback for the robot odometry.
Definition at line 1118 of file openni_listener.cpp.
void OpenNIListener::pcdCallback | ( | const sensor_msgs::ImageConstPtr | visual_img_msg, |
pointcloud_type::Ptr | point_cloud | ||
) |
Definition at line 535 of file openni_listener.cpp.
void OpenNIListener::processBagfile | ( | std::string | filename, |
const std::string & | visua_tpc, | ||
const std::string & | depth_tpc, | ||
const std::string & | points_tpc, | ||
const std::string & | cinfo_tpc, | ||
const std::string & | odom_tpc, | ||
const std::string & | tf_tpc | ||
) | [protected] |
processing the bagfile for loadBag
Definition at line 217 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
ODOMETRY
Definition at line 816 of file openni_listener.cpp.
void OpenNIListener::progress | ( | int | id, |
const char * | message, | ||
int | val | ||
) | [signal] |
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 947 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::setGUIInfo2 | ( | QString | message | ) | [signal] |
void OpenNIListener::setGUIStatus | ( | QString | message | ) | [signal] |
Set the temporary status-message in the GUI.
void OpenNIListener::setupSubscribers | ( | ) | [protected] |
Setup subscriber callbacks according to the topic parameters.
Definition at line 138 of file openni_listener.cpp.
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 558 of file openni_listener.cpp.
void OpenNIListener::togglePause | ( | ) | [slot] |
Switch between processing or ignoring new incoming data.
Definition at line 863 of file openni_listener.cpp.
void OpenNIListener::visualize_images | ( | cv::Mat | visual_image, |
cv::Mat | depth_image | ||
) | [protected] |
Definition at line 93 of file openni_listener.cpp.
void OpenNIListener::waitAndEvaluate | ( | const std::string & | filename | ) | [protected] |
delay after processing and trigger scientific evaluation
Definition at line 408 of file openni_listener.cpp.
BagSubscriber<sensor_msgs::CameraInfo>* OpenNIListener::cam_info_sub_ [protected] |
Definition at line 209 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::CameraInfo>* OpenNIListener::cinfo_sub_ [protected] |
Definition at line 203 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::PointCloud2>* OpenNIListener::cloud_sub_ [protected] |
Definition at line 204 of file openni_listener.h.
int OpenNIListener::data_id_ [protected] |
Definition at line 226 of file openni_listener.h.
BagSubscriber<sensor_msgs::Image>* OpenNIListener::depth_img_sub_ [protected] |
Definition at line 208 of file openni_listener.h.
cv::Mat OpenNIListener::depth_mono8_img_ [protected] |
Definition at line 212 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::Image>* OpenNIListener::depth_sub_ [protected] |
Definition at line 202 of file openni_listener.h.
cv::Ptr<cv::FeatureDetector> OpenNIListener::detector_ [protected] |
Definition at line 195 of file openni_listener.h.
cv::Ptr<cv::DescriptorExtractor> OpenNIListener::extractor_ [protected] |
Definition at line 196 of file openni_listener.h.
bool OpenNIListener::first_frame_ [protected] |
Definition at line 221 of file openni_listener.h.
QFuture<void> OpenNIListener::future_ [protected] |
Definition at line 222 of file openni_listener.h.
bool OpenNIListener::getOneFrame_ [protected] |
Definition at line 220 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 192 of file openni_listener.h.
std::string OpenNIListener::image_encoding_ [protected] |
Definition at line 228 of file openni_listener.h.
Definition at line 199 of file openni_listener.h.
Definition at line 200 of file openni_listener.h.
int OpenNIListener::num_processed_ [protected] |
Definition at line 227 of file openni_listener.h.
message_filters::Subscriber<nav_msgs::Odometry>* OpenNIListener::odom_sub_ [protected] |
Definition at line 205 of file openni_listener.h.
bool OpenNIListener::pause_ [protected] |
Definition at line 219 of file openni_listener.h.
BagSubscriber<sensor_msgs::PointCloud2>* OpenNIListener::pc_sub_ [protected] |
Definition at line 210 of file openni_listener.h.
BagSubscriber<sensor_msgs::Image>* OpenNIListener::rgb_img_sub_ [protected] |
Definition at line 207 of file openni_listener.h.
std::vector<cv::Mat> OpenNIListener::rgba_buffers_ [protected] |
Definition at line 217 of file openni_listener.h.
Definition at line 198 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 224 of file openni_listener.h.
ros::Publisher OpenNIListener::tf_pub_ [protected] |
Definition at line 225 of file openni_listener.h.
tf::TransformListener* OpenNIListener::tflistener_ [protected] |
Definition at line 223 of file openni_listener.h.
message_filters::Subscriber<sensor_msgs::Image>* OpenNIListener::visua_sub_ [protected] |
Definition at line 201 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 214 of file openni_listener.h.
cv::Mat OpenNIListener::visualization_img_ [protected] |
The visual img is stored here for visualization purposes here.
Definition at line 216 of file openni_listener.h.