Go to the documentation of this file.
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_msgs/GetNodeData.h"
54 #include "rtabmap_msgs/GetMap.h"
55 #include "rtabmap_msgs/GetMap2.h"
56 #include "rtabmap_msgs/ListLabels.h"
57 #include "rtabmap_msgs/PublishMap.h"
58 #include "rtabmap_msgs/SetGoal.h"
59 #include "rtabmap_msgs/SetLabel.h"
60 #include "rtabmap_msgs/RemoveLabel.h"
61 #include "rtabmap_msgs/Goal.h"
62 #include "rtabmap_msgs/GetPlan.h"
64 #include "rtabmap_msgs/OdomInfo.h"
65 #include "rtabmap_msgs/AddLink.h"
66 #include "rtabmap_msgs/GetNodesInRadius.h"
67 #include "rtabmap_msgs/LoadDatabase.h"
68 #include "rtabmap_msgs/DetectMoreLoopClosures.h"
69 #include "rtabmap_msgs/GlobalBundleAdjustment.h"
70 #include "rtabmap_msgs/CleanupLocalGrids.h"
75 #ifdef WITH_OCTOMAP_MSGS
76 #include <octomap_msgs/GetOctomap.h>
79 #ifdef WITH_APRILTAG_ROS
80 #include <apriltag_ros/AprilTagDetectionArray.h>
84 #ifdef WITH_FIDUCIAL_MSGS
85 #include <fiducial_msgs/FiducialTransformArray.h>
89 #include <move_base_msgs/MoveBaseAction.h>
90 #include <move_base_msgs/MoveBaseActionGoal.h>
91 #include <move_base_msgs/MoveBaseActionResult.h>
92 #include <move_base_msgs/MoveBaseActionFeedback.h>
93 #include <actionlib_msgs/GoalStatusArray.h>
116 const nav_msgs::OdometryConstPtr & odomMsg,
117 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
118 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
119 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
120 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
121 const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
122 const sensor_msgs::LaserScan& scanMsg,
123 const sensor_msgs::PointCloud2& scan3dMsg,
124 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
125 const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs = std::vector<rtabmap_msgs::GlobalDescriptor>(),
126 const std::vector<std::vector<rtabmap_msgs::KeyPoint> > & localKeyPoints = std::vector<std::vector<rtabmap_msgs::KeyPoint> >(),
127 const std::vector<std::vector<rtabmap_msgs::Point3f> > & localPoints3d = std::vector<std::vector<rtabmap_msgs::Point3f> >(),
128 const std::vector<cv::Mat> & localDescriptors = std::vector<cv::Mat>());
130 const std::string & odomFrameId,
131 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
132 const std::vector<cv_bridge::CvImageConstPtr> & imageMsgs,
133 const std::vector<cv_bridge::CvImageConstPtr> & depthMsgs,
134 const std::vector<sensor_msgs::CameraInfo> & cameraInfoMsgs,
135 const std::vector<sensor_msgs::CameraInfo> & depthCameraInfoMsgs,
136 const sensor_msgs::LaserScan& scan2dMsg,
137 const sensor_msgs::PointCloud2& scan3dMsg,
138 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
139 const std::vector<rtabmap_msgs::GlobalDescriptor> & globalDescriptorMsgs,
140 const std::vector<std::vector<rtabmap_msgs::KeyPoint> > & localKeyPoints,
141 const std::vector<std::vector<rtabmap_msgs::Point3f> > & localPoints3d,
142 const std::vector<cv::Mat> & localDescriptors);
144 const nav_msgs::OdometryConstPtr & odomMsg,
145 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
146 const sensor_msgs::LaserScan& scanMsg,
147 const sensor_msgs::PointCloud2& scan3dMsg,
148 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg,
149 const rtabmap_msgs::GlobalDescriptor & globalDescriptor = rtabmap_msgs::GlobalDescriptor());
151 const nav_msgs::OdometryConstPtr & odomMsg,
152 const rtabmap_msgs::UserDataConstPtr & userDataMsg,
153 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg);
155 const rtabmap_msgs::SensorDataConstPtr & sensorDataMsg,
156 const nav_msgs::OdometryConstPtr & odomMsg,
157 const rtabmap_msgs::OdomInfoConstPtr& odomInfoMsg);
164 #ifdef WITH_APRILTAG_ROS
165 void tagDetectionsAsyncCallback(
const apriltag_ros::AprilTagDetectionArray & tagDetections);
167 #ifdef WITH_FIDUCIAL_MSGS
168 void fiducialDetectionsAsyncCallback(
const fiducial_msgs::FiducialTransformArray & fiducialDetections);
173 void interOdomInfoCallback(
const nav_msgs::OdometryConstPtr & msg1,
const rtabmap_msgs::OdomInfoConstPtr & msg2);
178 const std::string & label,
182 double * planningTime = 0);
191 const std::vector<float> & odomVelocity = std::vector<float>(),
192 const std::string & odomFrameId =
"",
193 const cv::Mat & odomCovariance = cv::Mat::eye(6,6,CV_64FC1),
195 double timeMsgConversion = 0.0);
197 const std::map<int, rtabmap::Transform> &
nodes,
204 bool loadDatabaseCallback(rtabmap_msgs::LoadDatabase::Request&, rtabmap_msgs::LoadDatabase::Response&);
212 bool setLogDebug(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
213 bool setLogInfo(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
214 bool setLogWarn(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
215 bool setLogError(std_srvs::Empty::Request&, std_srvs::Empty::Response&);
216 bool getNodeDataCallback(rtabmap_msgs::GetNodeData::Request& req, rtabmap_msgs::GetNodeData::Response&
res);
219 bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &
res);
223 bool publishMapCallback(rtabmap_msgs::PublishMap::Request&, rtabmap_msgs::PublishMap::Response&);
224 bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &
res);
226 bool setGoalCallback(rtabmap_msgs::SetGoal::Request& req, rtabmap_msgs::SetGoal::Response&
res);
228 bool setLabelCallback(rtabmap_msgs::SetLabel::Request& req, rtabmap_msgs::SetLabel::Response&
res);
229 bool listLabelsCallback(rtabmap_msgs::ListLabels::Request& req, rtabmap_msgs::ListLabels::Response&
res);
230 bool removeLabelCallback(rtabmap_msgs::RemoveLabel::Request& req, rtabmap_msgs::RemoveLabel::Response&
res);
231 bool addLinkCallback(rtabmap_msgs::AddLink::Request&, rtabmap_msgs::AddLink::Response&);
233 #ifdef WITH_OCTOMAP_MSGS
234 bool octomapBinaryCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &
res);
235 bool octomapFullCallback(octomap_msgs::GetOctomap::Request &req, octomap_msgs::GetOctomap::Response &
res);
241 void publishLoop(
double tfDelay,
double tfTolerance);
247 void goalFeedbackCb(
const move_base_msgs::MoveBaseFeedbackConstPtr& feedback);
359 #ifdef WITH_OCTOMAP_MSGS
382 std::map<int, std::pair<geometry_msgs::PoseWithCovarianceStamped, float> >
tags_;
384 std::map<double, rtabmap::Transform>
imus_;
389 std::list<std::pair<nav_msgs::Odometry, rtabmap_msgs::OdomInfo> >
interOdoms_;
412 void updateStatus(
const cv::Mat & covariance,
bool twoDMapping);
void loadParameters(const std::string &configFile, rtabmap::ParametersMap ¶meters)
void publishLocalPath(const ros::Time &stamp)
void updateStatus(const cv::Mat &covariance, bool twoDMapping)
double waitForTransformDuration_
virtual void commonLaserScanCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const rtabmap_msgs::GlobalDescriptor &globalDescriptor=rtabmap_msgs::GlobalDescriptor())
bool setLogError(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::Publisher mapPathPub_
bool latestNodeWasReached_
ros::Subscriber goalNodeSub_
bool addLinkCallback(rtabmap_msgs::AddLink::Request &, rtabmap_msgs::AddLink::Response &)
void gpsFixAsyncCallback(const sensor_msgs::NavSatFixConstPtr &gpsFixMsg)
double localizationThreshold_
virtual void commonSensorDataCallback(const rtabmap_msgs::SensorDataConstPtr &sensorDataMsg, const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
geometry_msgs::PoseWithCovarianceStamped globalPose_
ros::ServiceServer setGoalSrv_
ros::Publisher landmarksPub_
int genDepthFillHolesSize_
void process(const ros::Time &stamp, rtabmap::SensorData &data, const rtabmap::Transform &odom=rtabmap::Transform(), const std::vector< float > &odomVelocity=std::vector< float >(), const std::string &odomFrameId="", const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const rtabmap::OdometryInfo &odomInfo=rtabmap::OdometryInfo(), double timeMsgConversion=0.0)
ros::Publisher nextMetricGoalPub_
ros::Publisher labelsPub_
ros::Publisher globalPathNodesPub_
message_filters::Subscriber< rtabmap_msgs::OdomInfo > interOdomInfoSyncSub_
rtabmap::ParametersMap parameters_
message_filters::sync_policies::ExactTime< nav_msgs::Odometry, rtabmap_msgs::OdomInfo > MyExactInterOdomSyncPolicy
ros::Publisher localPathNodesPub_
bool getProbMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
ros::ServiceServer resumeSrv_
void goalNodeCallback(const rtabmap_msgs::GoalConstPtr &msg)
ros::ServiceServer removeLabelSrv_
ros::ServiceServer setLabelSrv_
std::list< std::pair< nav_msgs::Odometry, rtabmap_msgs::OdomInfo > > interOdoms_
std::map< int, rtabmap::Transform > filterNodesToAssemble(const std::map< int, rtabmap::Transform > &nodes, const rtabmap::Transform ¤tPose)
void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
void publishCurrentGoal(const ros::Time &stamp)
virtual void commonMultiCameraCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const sensor_msgs::LaserScan &scanMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs=std::vector< rtabmap_msgs::GlobalDescriptor >(), const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPoints=std::vector< std::vector< rtabmap_msgs::KeyPoint > >(), const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3d=std::vector< std::vector< rtabmap_msgs::Point3f > >(), const std::vector< cv::Mat > &localDescriptors=std::vector< cv::Mat >())
std::vector< float > lastPoseVelocity_
ros::Publisher localPathPub_
bool globalBundleAdjustmentCallback(rtabmap_msgs::GlobalBundleAdjustment::Request &, rtabmap_msgs::GlobalBundleAdjustment::Response &)
void commonMultiCameraCallbackImpl(const std::string &odomFrameId, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const std::vector< cv_bridge::CvImageConstPtr > &imageMsgs, const std::vector< cv_bridge::CvImageConstPtr > &depthMsgs, const std::vector< sensor_msgs::CameraInfo > &cameraInfoMsgs, const std::vector< sensor_msgs::CameraInfo > &depthCameraInfoMsgs, const sensor_msgs::LaserScan &scan2dMsg, const sensor_msgs::PointCloud2 &scan3dMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg, const std::vector< rtabmap_msgs::GlobalDescriptor > &globalDescriptorMsgs, const std::vector< std::vector< rtabmap_msgs::KeyPoint > > &localKeyPoints, const std::vector< std::vector< rtabmap_msgs::Point3f > > &localPoints3d, const std::vector< cv::Mat > &localDescriptors)
double genDepthFillHolesError_
void republishNodeDataCallback(const std_msgs::Int32MultiArray::ConstPtr &msg)
MoveBaseClient * mbClient_
ros::ServiceServer setLogWarnSrv_
ros::ServiceServer getNodesInRadiusSrv_
ros::Subscriber republishNodeDataSub_
ros::Subscriber globalPoseAsyncSub_
ros::ServiceServer globalBundleAdjustmentSrv_
ros::ServiceServer getProjMapSrv_
bool createIntermediateNodes_
bool cleanupLocalGridsCallback(rtabmap_msgs::CleanupLocalGrids::Request &, rtabmap_msgs::CleanupLocalGrids::Response &)
bool setModeMappingCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
rtabmap::Transform mapToOdom_
cout<< "Here is the matrix m:"<< endl<< m<< endl;Matrix< ptrdiff_t, 3, 1 > res
std::string groundTruthFrameId_
rtabmap::Transform lastPublishedMetricGoal_
ros::ServiceServer setLogErrorSrv_
std::map< double, rtabmap::Transform > imus_
bool setModeLocalizationCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
std::map< std::string, std::string > ParametersMap
void initialPoseCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &msg)
ros::ServiceServer listLabelsSrv_
bool resumeRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool setLogWarn(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::ServiceServer triggerNewMapSrv_
void setLocalizationThreshold(double value)
rtabmap::Transform currentMetricGoal_
message_filters::Synchronizer< MyExactInterOdomSyncPolicy > * interOdomSync_
ros::Publisher goalReachedPub_
ros::ServiceServer getNodeDataSrv_
void goalCommonCallback(int id, const std::string &label, const std::string &frameId, const rtabmap::Transform &pose, const ros::Time &stamp, double *planningTime=0)
bool detectMoreLoopClosuresCallback(rtabmap_msgs::DetectMoreLoopClosures::Request &, rtabmap_msgs::DetectMoreLoopClosures::Response &)
bool odomUpdate(const nav_msgs::OdometryConstPtr &odomMsg, ros::Time stamp)
void publishGlobalPath(const ros::Time &stamp)
ros::Subscriber initialPoseSub_
void goalFeedbackCb(const move_base_msgs::MoveBaseFeedbackConstPtr &feedback)
void goalDoneCb(const actionlib::SimpleClientGoalState &state, const move_base_msgs::MoveBaseResultConstPtr &result)
ros::ServiceServer getMapSrv_
ros::ServiceServer updateSrv_
bool odomTFUpdate(const ros::Time &stamp)
ros::ServiceServer loadDatabaseSrv_
bool getPlanNodesCallback(rtabmap_msgs::GetPlan::Request &req, rtabmap_msgs::GetPlan::Response &res)
bool updateRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
double mappingAltitudeDelta_
ros::ServiceServer getMapData2Srv_
ros::ServiceServer cancelGoalSrv_
boost::mutex mapToOdomMutex_
void globalPoseAsyncCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &globalPoseMsg)
ros::Subscriber fiducialTransfromsSub_
ros::ServiceServer publishMapDataSrv_
double landmarkDefaultLinVariance_
ros::Subscriber gpsFixAsyncSub_
ros::ServiceServer getPlanSrv_
double odomDefaultLinVariance_
ros::ServiceServer resetSrv_
bool getMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
boost::thread * transformThread_
tf2_ros::TransformBroadcaster tfBroadcaster_
ros::Subscriber userDataAsyncSub_
bool loadDatabaseCallback(rtabmap_msgs::LoadDatabase::Request &, rtabmap_msgs::LoadDatabase::Response &)
double odomDefaultAngVariance_
bool publishMapCallback(rtabmap_msgs::PublishMap::Request &, rtabmap_msgs::PublishMap::Response &)
ros::ServiceServer setModeLocalizationSrv_
bool setLogInfo(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
void defaultCallback(const sensor_msgs::ImageConstPtr &imageMsg)
ros::Publisher mapGraphPub_
ros::Publisher localGridObstacle_
std::string groundTruthBaseFrameId_
void interOdomInfoCallback(const nav_msgs::OdometryConstPtr &msg1, const rtabmap_msgs::OdomInfoConstPtr &msg2)
void updateGoal(const ros::Time &stamp)
ros::ServiceServer setLogDebugSrv_
void interOdomCallback(const nav_msgs::OdometryConstPtr &msg)
ros::Publisher localGridGround_
ros::Publisher mapDataPub_
ros::ServiceServer detectMoreLoopClosuresSrv_
bool alreadyRectifiedImages_
rtabmap::Transform lastPose_
void publishStats(const ros::Time &stamp)
bool pubLocPoseOnlyWhenLocalizing_
bool pauseRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool listLabelsCallback(rtabmap_msgs::ListLabels::Request &req, rtabmap_msgs::ListLabels::Response &res)
bool getGridMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
void imuAsyncCallback(const sensor_msgs::ImuConstPtr &tagDetections)
ros::Subscriber interOdomSub_
void publishLoop(double tfDelay, double tfTolerance)
bool getNodesInRadiusCallback(rtabmap_msgs::GetNodesInRadius::Request &, rtabmap_msgs::GetNodesInRadius::Response &)
LocalizationStatusTask localizationDiagnostic_
double localizationError_
bool lastPoseIntermediate_
std::map< int, std::pair< geometry_msgs::PoseWithCovarianceStamped, float > > tags_
ros::ServiceServer getGridMapSrv_
tf::TransformListener tfListener_
bool triggerNewMapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
bool getPlanCallback(nav_msgs::GetPlan::Request &req, nav_msgs::GetPlan::Response &res)
bool removeLabelCallback(rtabmap_msgs::RemoveLabel::Request &req, rtabmap_msgs::RemoveLabel::Response &res)
bool setGoalCallback(rtabmap_msgs::SetGoal::Request &req, rtabmap_msgs::SetGoal::Response &res)
image_transport::Subscriber defaultSub_
rtabmap_util::MapsManager mapsManager_
ros::Publisher odomCachePub_
bool setLogDebug(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
virtual void commonOdomCallback(const nav_msgs::OdometryConstPtr &odomMsg, const rtabmap_msgs::UserDataConstPtr &userDataMsg, const rtabmap_msgs::OdomInfoConstPtr &odomInfoMsg)
ros::ServiceServer pauseSrv_
int genDepthFillIterations_
std::map< std::string, float > rtabmapROSStats_
message_filters::Subscriber< nav_msgs::Odometry > interOdomSyncSub_
void saveParameters(const std::string &configFile)
bool getProjMapCallback(nav_msgs::GetMap::Request &req, nav_msgs::GetMap::Response &res)
ros::ServiceServer setModeMappingSrv_
ros::Publisher localizationPosePub_
bool cancelGoalCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool getNodeDataCallback(rtabmap_msgs::GetNodeData::Request &req, rtabmap_msgs::GetNodeData::Response &res)
bool getMapDataCallback(rtabmap_msgs::GetMap::Request &req, rtabmap_msgs::GetMap::Response &res)
ros::Publisher globalPathPub_
ros::Subscriber tagDetectionsSub_
rtabmap_util::ULogToRosout ulogToRosout_
actionlib::SimpleActionClient< move_base_msgs::MoveBaseAction > MoveBaseClient
bool getMapData2Callback(rtabmap_msgs::GetMap2::Request &req, rtabmap_msgs::GetMap2::Response &res)
std::string databasePath_
void goalCallback(const geometry_msgs::PoseStampedConstPtr &msg)
ros::ServiceServer setLogInfoSrv_
ros::ServiceServer getPlanNodesSrv_
bool setLabelCallback(rtabmap_msgs::SetLabel::Request &req, rtabmap_msgs::SetLabel::Response &res)
ros::ServiceServer getMapDataSrv_
double landmarkDefaultAngVariance_
ros::ServiceServer getProbMapSrv_
void userDataAsyncCallback(const rtabmap_msgs::UserDataConstPtr &dataMsg)
bool resetRtabmapCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
ros::ServiceServer addLinkSrv_
ros::ServiceServer cleanupLocalGridsSrv_
rtabmap::Rtabmap rtabmap_
ros::Publisher localGridEmpty_
ros::ServiceServer backupDatabase_
bool backupDatabaseCallback(std_srvs::Empty::Request &, std_srvs::Empty::Response &)
rtabmap_slam
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:43:58