Public Member Functions | Protected Member Functions | Private Types | Private Member Functions | Private Attributes
GuiWrapper Class Reference

#include <GuiWrapper.h>

Inheritance diagram for GuiWrapper:
Inheritance graph
[legend]

List of all members.

Public Member Functions

int exec ()
 GuiWrapper (int &argc, char **argv)
virtual ~GuiWrapper ()

Protected Member Functions

virtual void handleEvent (UEvent *anEvent)

Private Types

typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
nav_msgs::Odometry,
rtabmap_ros::OdomInfo,
sensor_msgs::Image,
sensor_msgs::CameraInfo > 
MyDepthOdomInfoSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
nav_msgs::Odometry,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::LaserScan > 
MyDepthScanSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< sensor_msgs::Image,
nav_msgs::Odometry,
sensor_msgs::Image,
sensor_msgs::CameraInfo > 
MyDepthSyncPolicy
typedef
message_filters::sync_policies::ExactTime
< rtabmap_ros::Info,
rtabmap_ros::MapData > 
MyInfoMapSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< nav_msgs::Odometry,
rtabmap_ros::OdomInfo,
sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
MyStereoOdomInfoSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< nav_msgs::Odometry,
sensor_msgs::LaserScan,
sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
MyStereoScanSyncPolicy
typedef
message_filters::sync_policies::ApproximateTime
< nav_msgs::Odometry,
sensor_msgs::Image,
sensor_msgs::Image,
sensor_msgs::CameraInfo,
sensor_msgs::CameraInfo > 
MyStereoSyncPolicy

Private Member Functions

void defaultCallback (const nav_msgs::OdometryConstPtr &odomMsg)
void depthCallback (const sensor_msgs::ImageConstPtr &imageMsg, const nav_msgs::OdometryConstPtr &odomMsg, const sensor_msgs::ImageConstPtr &imageDepthMsg, const sensor_msgs::CameraInfoConstPtr &camInfoMsg)
void depthOdomInfoCallback (const sensor_msgs::ImageConstPtr &imageMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const sensor_msgs::ImageConstPtr &depthMsg, const sensor_msgs::CameraInfoConstPtr &cameraInfoMsg)
void depthScanCallback (const sensor_msgs::ImageConstPtr &imageMsg, const nav_msgs::OdometryConstPtr &odomMsg, const sensor_msgs::ImageConstPtr &imageDepthMsg, const sensor_msgs::CameraInfoConstPtr &camInfoMsg, const sensor_msgs::LaserScanConstPtr &scanMsg)
void infoMapCallback (const rtabmap_ros::InfoConstPtr &infoMsg, const rtabmap_ros::MapDataConstPtr &mapMsg)
void processRequestedMap (const rtabmap_ros::MapData &map)
void setupCallbacks (bool subscribeDepth, bool subscribeLaserScan, bool subscribeOdomInfo, bool subscribeStereo, int queueSize)
void stereoCallback (const nav_msgs::OdometryConstPtr &odomMsg, const sensor_msgs::ImageConstPtr &leftImageMsg, const sensor_msgs::ImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfoConstPtr &leftCameraInfoMsg, const sensor_msgs::CameraInfoConstPtr &rightCameraInfoMsg)
void stereoOdomInfoCallback (const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_ros::OdomInfoConstPtr &odomInfoMsg, const sensor_msgs::ImageConstPtr &leftImageMsg, const sensor_msgs::ImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfoConstPtr &leftCameraInfoMsg, const sensor_msgs::CameraInfoConstPtr &rightCameraInfoMsg)
void stereoScanCallback (const nav_msgs::OdometryConstPtr &odomMsg, const sensor_msgs::LaserScanConstPtr &scanMsg, const sensor_msgs::ImageConstPtr &leftImageMsg, const sensor_msgs::ImageConstPtr &rightImageMsg, const sensor_msgs::CameraInfoConstPtr &leftCameraInfoMsg, const sensor_msgs::CameraInfoConstPtr &rightCameraInfoMsg)

Private Attributes

QApplication * app_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
cameraInfoLeft_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
cameraInfoRight_
message_filters::Subscriber
< sensor_msgs::CameraInfo > 
cameraInfoSub_
std::string cameraNodeName_
ros::Subscriber defaultSub_
message_filters::Synchronizer
< MyDepthOdomInfoSyncPolicy > * 
depthOdomInfoSync_
message_filters::Synchronizer
< MyDepthScanSyncPolicy > * 
depthScanSync_
message_filters::Synchronizer
< MyDepthSyncPolicy > * 
depthSync_
std::string frameId_
image_transport::SubscriberFilter imageDepthSub_
image_transport::SubscriberFilter imageRectLeft_
image_transport::SubscriberFilter imageRectRight_
image_transport::SubscriberFilter imageSub_
message_filters::Synchronizer
< MyInfoMapSyncPolicy > * 
infoMapSync_
message_filters::Subscriber
< rtabmap_ros::Info
infoTopic_
double lastOdomInfoUpdateTime_
rtabmap::MainWindowmainWindow_
message_filters::Subscriber
< rtabmap_ros::MapData > 
mapDataTopic_
message_filters::Subscriber
< rtabmap_ros::OdomInfo > 
odomInfoSub_
message_filters::Subscriber
< nav_msgs::Odometry > 
odomSub_
message_filters::Subscriber
< sensor_msgs::LaserScan > 
scanSub_
message_filters::Synchronizer
< MyStereoOdomInfoSyncPolicy > * 
stereoOdomInfoSync_
message_filters::Synchronizer
< MyStereoScanSyncPolicy > * 
stereoScanSync_
message_filters::Synchronizer
< MyStereoSyncPolicy > * 
stereoSync_
tf::TransformListener tfListener_
bool waitForTransform_

Detailed Description

Definition at line 61 of file GuiWrapper.h.


Member Typedef Documentation

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, nav_msgs::Odometry, rtabmap_ros::OdomInfo, sensor_msgs::Image, sensor_msgs::CameraInfo> GuiWrapper::MyDepthOdomInfoSyncPolicy [private]

Definition at line 168 of file GuiWrapper.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::LaserScan> GuiWrapper::MyDepthScanSyncPolicy [private]

Definition at line 153 of file GuiWrapper.h.

typedef message_filters::sync_policies::ApproximateTime< sensor_msgs::Image, nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::CameraInfo> GuiWrapper::MyDepthSyncPolicy [private]

Definition at line 160 of file GuiWrapper.h.

Definition at line 145 of file GuiWrapper.h.

typedef message_filters::sync_policies::ApproximateTime< nav_msgs::Odometry, rtabmap_ros::OdomInfo, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> GuiWrapper::MyStereoOdomInfoSyncPolicy [private]

Definition at line 194 of file GuiWrapper.h.

typedef message_filters::sync_policies::ApproximateTime< nav_msgs::Odometry, sensor_msgs::LaserScan, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> GuiWrapper::MyStereoScanSyncPolicy [private]

Definition at line 185 of file GuiWrapper.h.

typedef message_filters::sync_policies::ApproximateTime< nav_msgs::Odometry, sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::CameraInfo, sensor_msgs::CameraInfo> GuiWrapper::MyStereoSyncPolicy [private]

Definition at line 176 of file GuiWrapper.h.


Constructor & Destructor Documentation

GuiWrapper::GuiWrapper ( int &  argc,
char **  argv 
)

Definition at line 68 of file GuiWrapper.cpp.

GuiWrapper::~GuiWrapper ( ) [virtual]

Definition at line 138 of file GuiWrapper.cpp.


Member Function Documentation

void GuiWrapper::defaultCallback ( const nav_msgs::OdometryConstPtr &  odomMsg) [private]

Definition at line 384 of file GuiWrapper.cpp.

void GuiWrapper::depthCallback ( const sensor_msgs::ImageConstPtr &  imageMsg,
const nav_msgs::OdometryConstPtr &  odomMsg,
const sensor_msgs::ImageConstPtr &  imageDepthMsg,
const sensor_msgs::CameraInfoConstPtr &  camInfoMsg 
) [private]

Definition at line 401 of file GuiWrapper.cpp.

void GuiWrapper::depthOdomInfoCallback ( const sensor_msgs::ImageConstPtr &  imageMsg,
const nav_msgs::OdometryConstPtr &  odomMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg,
const sensor_msgs::ImageConstPtr &  depthMsg,
const sensor_msgs::CameraInfoConstPtr &  cameraInfoMsg 
) [private]

Definition at line 469 of file GuiWrapper.cpp.

void GuiWrapper::depthScanCallback ( const sensor_msgs::ImageConstPtr &  imageMsg,
const nav_msgs::OdometryConstPtr &  odomMsg,
const sensor_msgs::ImageConstPtr &  imageDepthMsg,
const sensor_msgs::CameraInfoConstPtr &  camInfoMsg,
const sensor_msgs::LaserScanConstPtr &  scanMsg 
) [private]

Definition at line 537 of file GuiWrapper.cpp.

Definition at line 169 of file GuiWrapper.cpp.

void GuiWrapper::handleEvent ( UEvent anEvent) [protected, virtual]

Implements UEventsHandler.

Definition at line 261 of file GuiWrapper.cpp.

void GuiWrapper::infoMapCallback ( const rtabmap_ros::InfoConstPtr &  infoMsg,
const rtabmap_ros::MapDataConstPtr &  mapMsg 
) [private]

Definition at line 174 of file GuiWrapper.cpp.

void GuiWrapper::processRequestedMap ( const rtabmap_ros::MapData &  map) [private]

Definition at line 218 of file GuiWrapper.cpp.

void GuiWrapper::setupCallbacks ( bool  subscribeDepth,
bool  subscribeLaserScan,
bool  subscribeOdomInfo,
bool  subscribeStereo,
int  queueSize 
) [private]

Definition at line 902 of file GuiWrapper.cpp.

void GuiWrapper::stereoCallback ( const nav_msgs::OdometryConstPtr &  odomMsg,
const sensor_msgs::ImageConstPtr &  leftImageMsg,
const sensor_msgs::ImageConstPtr &  rightImageMsg,
const sensor_msgs::CameraInfoConstPtr &  leftCameraInfoMsg,
const sensor_msgs::CameraInfoConstPtr &  rightCameraInfoMsg 
) [private]

Definition at line 811 of file GuiWrapper.cpp.

void GuiWrapper::stereoOdomInfoCallback ( const nav_msgs::OdometryConstPtr &  odomMsg,
const rtabmap_ros::OdomInfoConstPtr &  odomInfoMsg,
const sensor_msgs::ImageConstPtr &  leftImageMsg,
const sensor_msgs::ImageConstPtr &  rightImageMsg,
const sensor_msgs::CameraInfoConstPtr &  leftCameraInfoMsg,
const sensor_msgs::CameraInfoConstPtr &  rightCameraInfoMsg 
) [private]

Definition at line 719 of file GuiWrapper.cpp.

void GuiWrapper::stereoScanCallback ( const nav_msgs::OdometryConstPtr &  odomMsg,
const sensor_msgs::LaserScanConstPtr &  scanMsg,
const sensor_msgs::ImageConstPtr &  leftImageMsg,
const sensor_msgs::ImageConstPtr &  rightImageMsg,
const sensor_msgs::CameraInfoConstPtr &  leftCameraInfoMsg,
const sensor_msgs::CameraInfoConstPtr &  rightCameraInfoMsg 
) [private]

Definition at line 616 of file GuiWrapper.cpp.


Member Data Documentation

QApplication* GuiWrapper::app_ [private]

Definition at line 117 of file GuiWrapper.h.

message_filters::Subscriber<sensor_msgs::CameraInfo> GuiWrapper::cameraInfoLeft_ [private]

Definition at line 140 of file GuiWrapper.h.

message_filters::Subscriber<sensor_msgs::CameraInfo> GuiWrapper::cameraInfoRight_ [private]

Definition at line 141 of file GuiWrapper.h.

message_filters::Subscriber<sensor_msgs::CameraInfo> GuiWrapper::cameraInfoSub_ [private]

Definition at line 133 of file GuiWrapper.h.

std::string GuiWrapper::cameraNodeName_ [private]

Definition at line 119 of file GuiWrapper.h.

Definition at line 130 of file GuiWrapper.h.

Definition at line 169 of file GuiWrapper.h.

Definition at line 154 of file GuiWrapper.h.

Definition at line 161 of file GuiWrapper.h.

std::string GuiWrapper::frameId_ [private]

Definition at line 123 of file GuiWrapper.h.

Definition at line 132 of file GuiWrapper.h.

Definition at line 138 of file GuiWrapper.h.

Definition at line 139 of file GuiWrapper.h.

Definition at line 131 of file GuiWrapper.h.

Definition at line 146 of file GuiWrapper.h.

Definition at line 127 of file GuiWrapper.h.

Definition at line 120 of file GuiWrapper.h.

Definition at line 118 of file GuiWrapper.h.

message_filters::Subscriber<rtabmap_ros::MapData> GuiWrapper::mapDataTopic_ [private]

Definition at line 128 of file GuiWrapper.h.

message_filters::Subscriber<rtabmap_ros::OdomInfo> GuiWrapper::odomInfoSub_ [private]

Definition at line 135 of file GuiWrapper.h.

message_filters::Subscriber<nav_msgs::Odometry> GuiWrapper::odomSub_ [private]

Definition at line 134 of file GuiWrapper.h.

message_filters::Subscriber<sensor_msgs::LaserScan> GuiWrapper::scanSub_ [private]

Definition at line 136 of file GuiWrapper.h.

Definition at line 195 of file GuiWrapper.h.

Definition at line 186 of file GuiWrapper.h.

Definition at line 177 of file GuiWrapper.h.

Definition at line 125 of file GuiWrapper.h.

Definition at line 124 of file GuiWrapper.h.


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


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:25