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> 63 virtual bool handleEvent(
UEvent * anEvent);
66 void infoMapCallback(
const rtabmap_ros::InfoConstPtr & infoMsg,
const rtabmap_ros::MapDataConstPtr & mapMsg);
67 void goalPathCallback(
const rtabmap_ros::GoalConstPtr & goalMsg,
const nav_msgs::PathConstPtr & pathMsg);
68 void goalReachedCallback(
const std_msgs::BoolConstPtr & value);
70 virtual void commonDepthCallback(
71 const nav_msgs::OdometryConstPtr & odomMsg,
72 const rtabmap_ros::UserDataConstPtr & userDataMsg,
73 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
74 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
75 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
76 const sensor_msgs::LaserScan& scan2dMsg,
77 const sensor_msgs::PointCloud2& scan3dMsg,
78 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
79 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
80 const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
81 const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_ros::Point3f> >(),
82 const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>());
83 virtual void commonStereoCallback(
84 const nav_msgs::OdometryConstPtr & odomMsg,
85 const rtabmap_ros::UserDataConstPtr & userDataMsg,
88 const sensor_msgs::CameraInfo& leftCamInfoMsg,
89 const sensor_msgs::CameraInfo& rightCamInfoMsg,
90 const sensor_msgs::LaserScan& scan2dMsg,
91 const sensor_msgs::PointCloud2& scan3dMsg,
92 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
93 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
94 const std::vector<rtabmap_ros::KeyPoint> & localKeyPoints = std::vector<rtabmap_ros::KeyPoint>(),
95 const std::vector<rtabmap_ros::Point3f> & localPoints3d = std::vector<rtabmap_ros::Point3f>(),
96 const cv::Mat & localDescriptors = cv::Mat());
97 virtual void commonLaserScanCallback(
98 const nav_msgs::OdometryConstPtr & odomMsg,
99 const rtabmap_ros::UserDataConstPtr & userDataMsg,
100 const sensor_msgs::LaserScan& scan2dMsg,
101 const sensor_msgs::PointCloud2& scan3dMsg,
102 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
103 const rtabmap_ros::GlobalDescriptor & globalDescriptor = rtabmap_ros::GlobalDescriptor());
105 virtual void commonOdomCallback(
106 const nav_msgs::OdometryConstPtr & odomMsg,
107 const rtabmap_ros::UserDataConstPtr & userDataMsg,
108 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
110 void defaultCallback(
const nav_msgs::OdometryConstPtr & odomMsg);
112 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_
message_filters::Subscriber< rtabmap_ros::MapData > mapDataTopic_
double lastOdomInfoUpdateTime_
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_
message_filters::sync_policies::ExactTime< rtabmap_ros::Info, rtabmap_ros::MapData > MyInfoMapSyncPolicy