32 #include "rtabmap_ros/Info.h"    33 #include "rtabmap_ros/MapData.h"    34 #include "rtabmap_ros/OdomInfo.h"    35 #include "rtabmap_ros/Goal.h"    41 #include <geometry_msgs/TwistStamped.h>    42 #include <nav_msgs/Path.h>    43 #include <std_msgs/Bool.h>    50         class PreferencesDialog;
    64         virtual bool handleEvent(
UEvent * anEvent);
    67         void infoMapCallback(
const rtabmap_ros::InfoConstPtr & infoMsg, 
const rtabmap_ros::MapDataConstPtr & mapMsg);
    68         void goalPathCallback(
const rtabmap_ros::GoalConstPtr & goalMsg, 
const nav_msgs::PathConstPtr & pathMsg);
    69         void goalReachedCallback(
const std_msgs::BoolConstPtr & value);
    71         virtual void commonMultiCameraCallback(
    72                         const nav_msgs::OdometryConstPtr & odomMsg,
    73                         const rtabmap_ros::UserDataConstPtr & userDataMsg,
    74                         const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
    75                         const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
    76                         const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
    77                         const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
    78                         const sensor_msgs::LaserScan& scan2dMsg,
    79                         const sensor_msgs::PointCloud2& scan3dMsg,
    80                         const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
    81                         const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
    82                         const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
    83                         const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_ros::Point3f> >(),
    84                         const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>());
    85         virtual void commonStereoCallback(
    86                         const nav_msgs::OdometryConstPtr & odomMsg,
    87                         const rtabmap_ros::UserDataConstPtr & userDataMsg,
    90                         const sensor_msgs::CameraInfo& leftCamInfoMsg,
    91                         const sensor_msgs::CameraInfo& rightCamInfoMsg,
    92                         const sensor_msgs::LaserScan& scan2dMsg,
    93                         const sensor_msgs::PointCloud2& scan3dMsg,
    94                         const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
    95                         const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
    96                         const std::vector<rtabmap_ros::KeyPoint> & localKeyPoints = std::vector<rtabmap_ros::KeyPoint>(),
    97                         const std::vector<rtabmap_ros::Point3f> & localPoints3d = std::vector<rtabmap_ros::Point3f>(),
    98                         const cv::Mat & localDescriptors = cv::Mat());
    99         virtual void commonLaserScanCallback(
   100                         const nav_msgs::OdometryConstPtr & odomMsg,
   101                         const rtabmap_ros::UserDataConstPtr & userDataMsg,
   102                         const sensor_msgs::LaserScan& scan2dMsg,
   103                         const sensor_msgs::PointCloud2& scan3dMsg,
   104                         const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
   105                         const rtabmap_ros::GlobalDescriptor & globalDescriptor = rtabmap_ros::GlobalDescriptor());
   107         virtual void commonOdomCallback(
   108                         const nav_msgs::OdometryConstPtr & odomMsg,
   109                         const rtabmap_ros::UserDataConstPtr & userDataMsg,
   110                         const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
   112         void defaultCallback(
const nav_msgs::OdometryConstPtr & odomMsg);
   114         void processRequestedMap(
const rtabmap_ros::MapData & map);
 
message_filters::Synchronizer< MyGoalPathSyncPolicy > * goalPathSync_
message_filters::Subscriber< rtabmap_ros::Info > infoTopic_
message_filters::Subscriber< rtabmap_ros::Goal > goalTopic_
rtabmap::MainWindow * mainWindow_
rtabmap::PreferencesDialog * prefDialog_
message_filters::Subscriber< rtabmap_ros::MapData > mapDataTopic_
double lastOdomInfoUpdateTime_
std::string rtabmapNodeName_
double waitForTransformDuration_
ros::Subscriber goalReachedTopic_
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
double maxOdomUpdateRate_
tf::TransformListener tfListener_
message_filters::sync_policies::ExactTime< rtabmap_ros::Goal, nav_msgs::Path > MyGoalPathSyncPolicy
std::string cameraNodeName_
message_filters::Subscriber< nav_msgs::Path > pathTopic_
ros::Publisher republishNodeDataPub_
message_filters::sync_policies::ExactTime< rtabmap_ros::Info, rtabmap_ros::MapData > MyInfoMapSyncPolicy