28 #ifndef COREWRAPPER_H_ 29 #define COREWRAPPER_H_ 35 #include <std_srvs/Empty.h> 40 #include <std_msgs/Empty.h> 41 #include <std_msgs/Int32.h> 42 #include <nav_msgs/GetMap.h> 43 #include <nav_msgs/GetPlan.h> 44 #include <geometry_msgs/PoseWithCovarianceStamped.h> 50 #include "rtabmap_ros/GetMap.h" 51 #include "rtabmap_ros/ListLabels.h" 52 #include "rtabmap_ros/PublishMap.h" 53 #include "rtabmap_ros/SetGoal.h" 54 #include "rtabmap_ros/SetLabel.h" 55 #include "rtabmap_ros/Goal.h" 60 #ifdef WITH_OCTOMAP_MSGS 61 #include <octomap_msgs/GetOctomap.h> 65 #include <move_base_msgs/MoveBaseAction.h> 66 #include <move_base_msgs/MoveBaseActionGoal.h> 67 #include <move_base_msgs/MoveBaseActionResult.h> 68 #include <move_base_msgs/MoveBaseActionFeedback.h> 69 #include <actionlib_msgs/GoalStatusArray.h> 86 virtual void onInit();
88 bool odomUpdate(
const nav_msgs::OdometryConstPtr & odomMsg,
ros::Time stamp);
89 bool odomTFUpdate(
const ros::Time & stamp);
91 virtual void commonDepthCallback(
92 const nav_msgs::OdometryConstPtr & odomMsg,
93 const rtabmap_ros::UserDataConstPtr & userDataMsg,
94 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
95 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
96 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
97 const sensor_msgs::LaserScanConstPtr& scanMsg,
98 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
99 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
100 void commonDepthCallbackImpl(
101 const std::string & odomFrameId,
102 const rtabmap_ros::UserDataConstPtr & userDataMsg,
103 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
104 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
105 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
106 const sensor_msgs::LaserScanConstPtr& scan2dMsg,
107 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
108 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
109 virtual void commonStereoCallback(
110 const nav_msgs::OdometryConstPtr & odomMsg,
111 const rtabmap_ros::UserDataConstPtr & userDataMsg,
114 const sensor_msgs::CameraInfo& leftCamInfoMsg,
115 const sensor_msgs::CameraInfo& rightCamInfoMsg,
116 const sensor_msgs::LaserScanConstPtr& scanMsg,
117 const sensor_msgs::PointCloud2ConstPtr& scan3dMsg,
118 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
120 void defaultCallback(
const sensor_msgs::ImageConstPtr & imageMsg);
122 void userDataAsyncCallback(
const rtabmap_ros::UserDataConstPtr & dataMsg);
123 void globalPoseAsyncCallback(
const geometry_msgs::PoseWithCovarianceStampedConstPtr & globalPoseMsg);
125 void initialPoseCallback(
const geometry_msgs::PoseWithCovarianceStampedConstPtr & msg);
127 void goalCommonCallback(
int id,
const std::string & label,
const rtabmap::Transform & pose,
const ros::Time & stamp,
double * planningTime = 0);
128 void goalCallback(
const geometry_msgs::PoseStampedConstPtr & msg);
129 void goalNodeCallback(
const rtabmap_ros::GoalConstPtr & msg);
130 void updateGoal(
const ros::Time & stamp);
136 const std::string & odomFrameId =
"",
137 const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
140 bool updateRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
141 bool resetRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
142 bool pauseRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
143 bool resumeRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
144 bool triggerNewMapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
145 bool backupDatabaseCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
146 bool setModeLocalizationCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
147 bool setModeMappingCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
148 bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
149 bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
150 bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
151 bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
152 bool getMapDataCallback(rtabmap_ros::GetMap::Request& req, rtabmap_ros::GetMap::Response& res);
153 bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
154 bool getProbMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
155 bool getProjMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
156 bool getGridMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
157 bool publishMapCallback(rtabmap_ros::PublishMap::Request&, rtabmap_ros::PublishMap::Response&);
158 bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res);
159 bool setGoalCallback(rtabmap_ros::SetGoal::Request& req, rtabmap_ros::SetGoal::Response& res);
160 bool cancelGoalCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
161 bool setLabelCallback(rtabmap_ros::SetLabel::Request& req, rtabmap_ros::SetLabel::Response& res);
162 bool listLabelsCallback(rtabmap_ros::ListLabels::Request& req, rtabmap_ros::ListLabels::Response& res);
163 #ifdef WITH_OCTOMAP_MSGS 164 bool octomapBinaryCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
165 bool octomapFullCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
169 void saveParameters(
const std::string & configFile);
171 void publishLoop(
double tfDelay,
double tfTolerance);
173 void publishStats(
const ros::Time & stamp);
174 void publishCurrentGoal(
const ros::Time & stamp);
177 void goalFeedbackCb(
const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
178 void publishLocalPath(
const ros::Time & stamp);
179 void publishGlobalPath(
const ros::Time & stamp);
259 #ifdef WITH_OCTOMAP_MSGS geometry_msgs::PoseWithCovarianceStamped globalPose_
ros::ServiceServer setLogErrorSrv_
ros::ServiceServer getMapDataSrv_
ros::ServiceServer getProjMapSrv_
ros::ServiceServer pauseSrv_
#define DATA_SYNCS3(PREFIX, MSG0, MSG1, MSG2)
ros::ServiceServer setLogDebugSrv_
rtabmap::Transform lastPose_
ros::ServiceServer publishMapDataSrv_
double odomDefaultLinVariance_
ros::ServiceServer setLogWarnSrv_
image_transport::Subscriber defaultSub_
#define DATA_SYNCS2(PREFIX, MSG0, MSG1)
ros::ServiceServer resetSrv_
rtabmap::ParametersMap parameters_
bool createIntermediateNodes_
ros::ServiceServer getMapSrv_
ros::ServiceServer getGridMapSrv_
rtabmap::Rtabmap rtabmap_
ros::Publisher localizationPosePub_
rtabmap::Transform lastPublishedMetricGoal_
std::map< std::string, std::string > ParametersMap
ros::ServiceServer getProbMapSrv_
bool lastPoseIntermediate_
std::string databasePath_
ros::Publisher nextMetricGoalPub_
ros::Subscriber initialPoseSub_
ros::Publisher mapDataPub_
ros::Subscriber globalPoseAsyncSub_
ros::ServiceServer setModeMappingSrv_
ros::Subscriber userDataAsyncSub_
double odomDefaultAngVariance_
ros::ServiceServer updateSrv_
bool latestNodeWasReached_
ros::ServiceServer backupDatabase_
ros::ServiceServer setLogInfoSrv_
std::map< std::string, float > rtabmapROSStats_
ros::ServiceServer setLabelSrv_
tf2_ros::TransformBroadcaster tfBroadcaster_
message_filters::Subscriber< nav_msgs::Odometry > rgbOdomSub_
boost::mutex mapToOdomMutex_
ros::ServiceServer cancelGoalSrv_
tf::TransformListener tfListener_
RecoveryProgressState state
rtabmap::Transform mapToOdom_
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
boost::thread * transformThread_
rtabmap::Transform currentMetricGoal_
message_filters::Subscriber< sensor_msgs::CameraInfo > rgbCameraInfoSub_
image_transport::SubscriberFilter rgbSub_
ros::Subscriber goalNodeSub_
ros::ServiceServer listLabelsSrv_
ros::Publisher labelsPub_
ros::Publisher mapPathPub_
ros::Publisher localPathPub_
double waitForTransformDuration_
std::string groundTruthFrameId_
ros::ServiceServer getPlanSrv_
ros::ServiceServer setGoalSrv_
ros::Publisher globalPathPub_
std::string groundTruthBaseFrameId_
ros::ServiceServer setModeLocalizationSrv_
ros::Publisher goalReachedPub_
ros::ServiceServer triggerNewMapSrv_
ros::Publisher mapGraphPub_
ros::ServiceServer resumeSrv_