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::LaserScanConstPtr& scan2dMsg,
77 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
78 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
79 virtual void commonStereoCallback(
80 const nav_msgs::OdometryConstPtr & odomMsg,
81 const rtabmap_ros::UserDataConstPtr & userDataMsg,
84 const sensor_msgs::CameraInfo& leftCamInfoMsg,
85 const sensor_msgs::CameraInfo& rightCamInfoMsg,
86 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
87 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
88 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
90 void defaultCallback(
const nav_msgs::OdometryConstPtr & odomMsg);
92 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 defaultSub_
ros::Subscriber goalReachedTopic_
message_filters::Synchronizer< MyInfoMapSyncPolicy > * infoMapSync_
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