Public Slots | Signals | Public Member Functions | Protected Member Functions | Protected Attributes
BagLoader Class Reference

Handles most of the ROS-based communication. More...

#include <bagloader.h>

List of all members.

Public Slots

void clearPointCloud (pointcloud_type *)
void loadBagFileAsync (QString)
void loadBagFileAsync (std::string)
void togglePause ()
 Switch between processing or ignoring new incoming data.

Signals

void bagFinished ()
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.
void setPointCloud (pointcloud_type *pc, QMatrix4x4 transformation)
 QT Stuff, to communicate with the gui.

Public Member Functions

 BagLoader ()
 Ctor: setup synced listening to ros topics (kinect/stereo data) and prepare the feature handling.
void callback (const sensor_msgs::PointCloud2ConstPtr &point_cloud)
 ~BagLoader ()
 Delete tflistener, shutdown ros publishers.

Protected Member Functions

void loadBag (std::string filename)
 Load data from bag file.
void sendWithTransformation (pointcloud_type *cloud)
 Retrieve the transform between the lens and the base-link at capturing time.

Protected Attributes

rosbag::Bag bag
int data_id_
bool pause_
ros::Publisher tf_pub_
 this being a pointer saves the include (using the above forward declaration)
tf::TransformListenertflistener_

Detailed Description

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 48 of file bagloader.h.


Constructor & Destructor Documentation

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 49 of file bagloader.cpp.

Delete tflistener, shutdown ros publishers.

Definition at line 154 of file bagloader.cpp.


Member Function Documentation

void BagLoader::bagFinished ( ) [signal]
void BagLoader::callback ( const sensor_msgs::PointCloud2ConstPtr &  point_cloud)

Definition at line 139 of file bagloader.cpp.

Definition at line 201 of file bagloader.cpp.

void BagLoader::loadBag ( std::string  filename) [protected]

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 61 of file bagloader.cpp.

void BagLoader::loadBagFileAsync ( QString  file) [slot]

Definition at line 196 of file bagloader.cpp.

void BagLoader::loadBagFileAsync ( std::string  file) [slot]

Definition at line 191 of file bagloader.cpp.

void BagLoader::sendWithTransformation ( pointcloud_type cloud) [protected]

Retrieve the transform between the lens and the base-link at capturing time.

Definition at line 168 of file bagloader.cpp.

void BagLoader::setGUIInfo ( QString  message) [signal]

Set the info label on the right side in the statusbar of the GUI.

void BagLoader::setGUIInfo2 ( QString  message) [signal]
void BagLoader::setGUIStatus ( QString  message) [signal]

Set the temporary status-message in the GUI.

void BagLoader::setPointCloud ( pointcloud_type pc,
QMatrix4x4  transformation 
) [signal]

QT Stuff, to communicate with the gui.

void BagLoader::togglePause ( ) [slot]

Switch between processing or ignoring new incoming data.

Definition at line 160 of file bagloader.cpp.


Member Data Documentation

Definition at line 84 of file bagloader.h.

int BagLoader::data_id_ [protected]

Definition at line 91 of file bagloader.h.

bool BagLoader::pause_ [protected]

Definition at line 88 of file bagloader.h.

this being a pointer saves the include (using the above forward declaration)

Definition at line 90 of file bagloader.h.

Definition at line 89 of file bagloader.h.


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


rgbdslam_v2
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Thu Jun 6 2019 21:49:45