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 "std_msgs/Int32MultiArray.h" 43 #include <sensor_msgs/NavSatFix.h> 44 #include <nav_msgs/GetMap.h> 45 #include <nav_msgs/GetPlan.h> 46 #include <geometry_msgs/PoseWithCovarianceStamped.h> 47 #include <sensor_msgs/Imu.h> 53 #include "rtabmap_ros/GetNodeData.h" 54 #include "rtabmap_ros/GetMap.h" 55 #include "rtabmap_ros/GetMap2.h" 56 #include "rtabmap_ros/ListLabels.h" 57 #include "rtabmap_ros/PublishMap.h" 58 #include "rtabmap_ros/SetGoal.h" 59 #include "rtabmap_ros/SetLabel.h" 60 #include "rtabmap_ros/RemoveLabel.h" 61 #include "rtabmap_ros/Goal.h" 62 #include "rtabmap_ros/GetPlan.h" 64 #include "rtabmap_ros/OdomInfo.h" 65 #include "rtabmap_ros/AddLink.h" 66 #include "rtabmap_ros/GetNodesInRadius.h" 67 #include "rtabmap_ros/LoadDatabase.h" 68 #include "rtabmap_ros/DetectMoreLoopClosures.h" 69 #include "rtabmap_ros/GlobalBundleAdjustment.h" 70 #include "rtabmap_ros/CleanupLocalGrids.h" 76 #ifdef WITH_OCTOMAP_MSGS 77 #include <octomap_msgs/GetOctomap.h> 80 #ifdef WITH_APRILTAG_ROS 81 #include <apriltag_ros/AprilTagDetectionArray.h> 85 #ifdef WITH_FIDUCIAL_MSGS 86 #include <fiducial_msgs/FiducialTransformArray.h> 90 #include <move_base_msgs/MoveBaseAction.h> 91 #include <move_base_msgs/MoveBaseActionGoal.h> 92 #include <move_base_msgs/MoveBaseActionResult.h> 93 #include <move_base_msgs/MoveBaseActionFeedback.h> 94 #include <actionlib_msgs/GoalStatusArray.h> 111 virtual void onInit();
113 bool odomUpdate(
const nav_msgs::OdometryConstPtr & odomMsg,
ros::Time stamp);
114 bool odomTFUpdate(
const ros::Time & stamp);
116 virtual void commonMultiCameraCallback(
117 const nav_msgs::OdometryConstPtr & odomMsg,
118 const rtabmap_ros::UserDataConstPtr & userDataMsg,
119 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
120 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
121 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
122 const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
123 const sensor_msgs::LaserScan& scanMsg,
124 const sensor_msgs::PointCloud2& scan3dMsg,
125 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
126 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_ros::GlobalDescriptor>(),
127 const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_ros::KeyPoint> >(),
128 const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_ros::Point3f> >(),
129 const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>());
130 void commonMultiCameraCallbackImpl(
131 const std::string & odomFrameId,
132 const rtabmap_ros::UserDataConstPtr & userDataMsg,
133 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
134 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
135 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
136 const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
137 const sensor_msgs::LaserScan& scan2dMsg,
138 const sensor_msgs::PointCloud2& scan3dMsg,
139 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
140 const std::vector<rtabmap_ros::GlobalDescriptor> & globalDescriptorMsgs,
141 const std::vector<std::vector<rtabmap_ros::KeyPoint> > & localKeyPoints,
142 const std::vector<std::vector<rtabmap_ros::Point3f> > & localPoints3d,
143 const std::vector<cv::Mat> & localDescriptors);
144 virtual void commonLaserScanCallback(
145 const nav_msgs::OdometryConstPtr & odomMsg,
146 const rtabmap_ros::UserDataConstPtr & userDataMsg,
147 const sensor_msgs::LaserScan& scanMsg,
148 const sensor_msgs::PointCloud2& scan3dMsg,
149 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg,
150 const rtabmap_ros::GlobalDescriptor & globalDescriptor = rtabmap_ros::GlobalDescriptor());
151 virtual void commonOdomCallback(
152 const nav_msgs::OdometryConstPtr & odomMsg,
153 const rtabmap_ros::UserDataConstPtr & userDataMsg,
154 const rtabmap_ros::OdomInfoConstPtr& odomInfoMsg);
156 void defaultCallback(
const sensor_msgs::ImageConstPtr & imageMsg);
158 void userDataAsyncCallback(
const rtabmap_ros::UserDataConstPtr & dataMsg);
159 void globalPoseAsyncCallback(
const geometry_msgs::PoseWithCovarianceStampedConstPtr & globalPoseMsg);
160 void gpsFixAsyncCallback(
const sensor_msgs::NavSatFixConstPtr & gpsFixMsg);
161 #ifdef WITH_APRILTAG_ROS 162 void tagDetectionsAsyncCallback(
const apriltag_ros::AprilTagDetectionArray & tagDetections);
164 #ifdef WITH_FIDUCIAL_MSGS 165 void fiducialDetectionsAsyncCallback(
const fiducial_msgs::FiducialTransformArray & fiducialDetections);
167 void imuAsyncCallback(
const sensor_msgs::ImuConstPtr & tagDetections);
168 void republishNodeDataCallback(
const std_msgs::Int32MultiArray::ConstPtr& msg);
169 void interOdomCallback(
const nav_msgs::OdometryConstPtr & msg);
170 void interOdomInfoCallback(
const nav_msgs::OdometryConstPtr & msg1,
const rtabmap_ros::OdomInfoConstPtr & msg2);
172 void initialPoseCallback(
const geometry_msgs::PoseWithCovarianceStampedConstPtr & msg);
174 void goalCommonCallback(
int id,
175 const std::string & label,
179 double * planningTime = 0);
180 void goalCallback(
const geometry_msgs::PoseStampedConstPtr & msg);
181 void goalNodeCallback(
const rtabmap_ros::GoalConstPtr & msg);
182 void updateGoal(
const ros::Time & stamp);
188 const std::vector<float> & odomVelocity = std::vector<float>(),
189 const std::string & odomFrameId =
"",
190 const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
192 double timeMsgConversion = 0.0);
193 std::map<int, rtabmap::Transform> filterNodesToAssemble(
194 const std::map<int, rtabmap::Transform> & nodes,
197 bool updateRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
198 bool resetRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
199 bool pauseRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
200 bool resumeRtabmapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
201 bool loadDatabaseCallback(rtabmap_ros::LoadDatabase::Request&, rtabmap_ros::LoadDatabase::Response&);
202 bool triggerNewMapCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
203 bool backupDatabaseCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
204 bool detectMoreLoopClosuresCallback(rtabmap_ros::DetectMoreLoopClosures::Request&, rtabmap_ros::DetectMoreLoopClosures::Response&);
205 bool globalBundleAdjustmentCallback(rtabmap_ros::GlobalBundleAdjustment::Request&, rtabmap_ros::GlobalBundleAdjustment::Response&);
206 bool cleanupLocalGridsCallback(rtabmap_ros::CleanupLocalGrids::Request&, rtabmap_ros::CleanupLocalGrids::Response&);
207 bool setModeLocalizationCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
208 bool setModeMappingCallback(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
209 bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
210 bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
211 bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
212 bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
213 bool getNodeDataCallback(rtabmap_ros::GetNodeData::Request& req, rtabmap_ros::GetNodeData::Response&
res);
214 bool getMapDataCallback(rtabmap_ros::GetMap::Request& req, rtabmap_ros::GetMap::Response& res);
215 bool getMapData2Callback(rtabmap_ros::GetMap2::Request& req, rtabmap_ros::GetMap2::Response& res);
216 bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
217 bool getProbMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
218 bool getProjMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
219 bool getGridMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res);
220 bool publishMapCallback(rtabmap_ros::PublishMap::Request&, rtabmap_ros::PublishMap::Response&);
221 bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res);
222 bool getPlanNodesCallback(rtabmap_ros::GetPlan::Request &req, rtabmap_ros::GetPlan::Response &res);
223 bool setGoalCallback(rtabmap_ros::SetGoal::Request& req, rtabmap_ros::SetGoal::Response& res);
224 bool cancelGoalCallback(std_srvs::Empty::Request& req, std_srvs::Empty::Response& res);
225 bool setLabelCallback(rtabmap_ros::SetLabel::Request& req, rtabmap_ros::SetLabel::Response& res);
226 bool listLabelsCallback(rtabmap_ros::ListLabels::Request& req, rtabmap_ros::ListLabels::Response& res);
227 bool removeLabelCallback(rtabmap_ros::RemoveLabel::Request& req, rtabmap_ros::RemoveLabel::Response& res);
228 bool addLinkCallback(rtabmap_ros::AddLink::Request&, rtabmap_ros::AddLink::Response&);
229 bool getNodesInRadiusCallback(rtabmap_ros::GetNodesInRadius::Request&, rtabmap_ros::GetNodesInRadius::Response&);
230 #ifdef WITH_OCTOMAP_MSGS 231 bool octomapBinaryCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
232 bool octomapFullCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &res);
236 void saveParameters(
const std::string & configFile);
238 void publishLoop(
double tfDelay,
double tfTolerance);
240 void publishStats(
const ros::Time & stamp);
241 void publishCurrentGoal(
const ros::Time & stamp);
244 void goalFeedbackCb(
const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
245 void publishLocalPath(
const ros::Time & stamp);
246 void publishGlobalPath(
const ros::Time & stamp);
247 void republishMaps();
354 #ifdef WITH_OCTOMAP_MSGS 377 std::map<int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> >
tags_;
379 std::map<double, rtabmap::Transform>
imus_;
384 std::list<std::pair<nav_msgs::Odometry, rtabmap_ros::OdomInfo> >
interOdoms_;
geometry_msgs::PoseWithCovarianceStamped globalPose_
ros::ServiceServer setLogErrorSrv_
ros::ServiceServer getMapDataSrv_
ros::Subscriber gpsFixAsyncSub_
ros::ServiceServer getNodesInRadiusSrv_
ros::ServiceServer getProjMapSrv_
int genDepthFillIterations_
double genDepthFillHolesError_
ros::ServiceServer pauseSrv_
ros::Publisher localPathNodesPub_
ros::Subscriber republishNodeDataSub_
ros::ServiceServer setLogDebugSrv_
rtabmap::Transform lastPose_
double mappingAltitudeDelta_
ros::Publisher globalPathNodesPub_
ros::ServiceServer publishMapDataSrv_
ros::ServiceServer detectMoreLoopClosuresSrv_
double odomDefaultLinVariance_
ros::ServiceServer setLogWarnSrv_
image_transport::Subscriber defaultSub_
ros::ServiceServer resetSrv_
rtabmap::ParametersMap parameters_
bool createIntermediateNodes_
ros::ServiceServer addLinkSrv_
ros::Subscriber tagDetectionsSub_
ros::Publisher localGridEmpty_
ros::ServiceServer getNodeDataSrv_
ros::ServiceServer getMapSrv_
ros::ServiceServer getGridMapSrv_
rtabmap::Rtabmap rtabmap_
ros::ServiceServer removeLabelSrv_
ros::Publisher localizationPosePub_
ros::Subscriber fiducialTransfromsSub_
rtabmap::Transform lastPublishedMetricGoal_
message_filters::Synchronizer< MyExactInterOdomSyncPolicy > * interOdomSync_
std::map< std::string, std::string > ParametersMap
message_filters::sync_policies::ExactTime< nav_msgs::Odometry, rtabmap_ros::OdomInfo > MyExactInterOdomSyncPolicy
ros::ServiceServer getProbMapSrv_
ULogToRosout ulogToRosout_
double landmarkDefaultAngVariance_
ros::Publisher landmarksPub_
bool lastPoseIntermediate_
message_filters::Subscriber< rtabmap_ros::OdomInfo > interOdomInfoSyncSub_
int genDepthFillHolesSize_
std::string databasePath_
ros::ServiceServer getMapData2Srv_
ros::ServiceServer cleanupLocalGridsSrv_
ros::Publisher nextMetricGoalPub_
ros::Subscriber initialPoseSub_
ros::Publisher mapDataPub_
bool alreadyRectifiedImages_
ros::Subscriber globalPoseAsyncSub_
ros::ServiceServer globalBundleAdjustmentSrv_
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::Subscriber interOdomSub_
ros::ServiceServer setLabelSrv_
tf2_ros::TransformBroadcaster tfBroadcaster_
ros::Publisher localGridObstacle_
message_filters::Subscriber< nav_msgs::Odometry > interOdomSyncSub_
MoveBaseClient * mbClient_
boost::mutex mapToOdomMutex_
ros::ServiceServer cancelGoalSrv_
tf::TransformListener tfListener_
RecoveryProgressState state
double landmarkDefaultLinVariance_
rtabmap::Transform mapToOdom_
std::vector< float > lastPoseVelocity_
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
ros::Publisher odomCachePub_
boost::thread * transformThread_
rtabmap::Transform currentMetricGoal_
ros::Subscriber goalNodeSub_
ros::ServiceServer listLabelsSrv_
ros::Publisher labelsPub_
ros::Publisher mapPathPub_
ros::ServiceServer getPlanNodesSrv_
ros::Publisher localPathPub_
std::map< int, std::pair< geometry_msgs::PoseWithCovarianceStamped, float > > tags_
double waitForTransformDuration_
std::string groundTruthFrameId_
std::map< double, rtabmap::Transform > imus_
ros::ServiceServer loadDatabaseSrv_
ros::ServiceServer getPlanSrv_
std::list< std::pair< nav_msgs::Odometry, rtabmap_ros::OdomInfo > > interOdoms_
ros::ServiceServer setGoalSrv_
ros::Publisher globalPathPub_
std::string groundTruthBaseFrameId_
ros::ServiceServer setModeLocalizationSrv_
ros::Publisher goalReachedPub_
ros::ServiceServer triggerNewMapSrv_
ros::Publisher mapGraphPub_
ros::Publisher localGridGround_
ros::ServiceServer resumeSrv_