Go to the documentation of this file.
   29 #include <ros/publisher.h> 
   32 #include <rtabmap_msgs/MapData.h> 
   33 #include <rtabmap_msgs/Info.h> 
   35 #include <rtabmap_msgs/AddLink.h> 
   36 #include <rtabmap_msgs/GetMap.h> 
   74 void mapDataCallback(
const rtabmap_msgs::MapDataConstPtr & mapDataMsg, 
const rtabmap_msgs::InfoConstPtr & infoMsg)
 
   81         bool smallMovement = (bool)
uValue(
stats.data(), rtabmap::Statistics::kMemorySmall_movement(), 0.0f);
 
   82         bool fastMovement = (bool)
uValue(
stats.data(), rtabmap::Statistics::kMemoryFast_movement(), 0.0f);
 
   84         if(smallMovement || fastMovement)
 
   91         std::map<int, rtabmap::Transform> poses;
 
   92         std::multimap<int, rtabmap::Link> links;
 
   93         std::map<int, rtabmap::Signature> signatures;
 
   96         if(!signatures.empty() &&
 
   97                 signatures.rbegin()->second.sensorData().isValid() &&
 
  100                 int id = signatures.rbegin()->first;
 
  113                                 ROS_INFO(
"Detected loop closure between %d and %d", fromId, toId);
 
  127                                                 rtabmap_msgs::AddLinkRequest req;
 
  129                                                 rtabmap_msgs::AddLinkResponse 
res;
 
  137                                                 ROS_WARN(
"Could not compute transformation between %d and %d: %s", fromId, toId, regInfo.
rejectedMsg.c_str());
 
  142                                         ROS_WARN(
"Could not compute transformation between %d and %d because node data %d is not in cache.", fromId, toId, toId);
 
  153 int main(
int argc, 
char** argv)
 
  176         rtabmap_msgs::GetMap::Request mapReq;
 
  177         mapReq.global = 
true;
 
  178         mapReq.graphOnly = 
false;
 
  179         mapReq.optimized = 
false;
 
  180         rtabmap_msgs::GetMap::Response mapRes;
 
  184                 ROS_INFO(
"Waiting for service \"%s\" to be available. If rtabmap is already started, " 
  194         if(
getMapSrv.
call(mapReq, mapRes) && !mapRes.data.nodes.empty())
 
  196                 ROS_INFO(
"Adding %d nodes to memory...", (
int)mapRes.data.nodes.size());
 
  197                 std::map<int, rtabmap::Transform> poses;
 
  198                 std::multimap<int, rtabmap::Link> links;
 
  202                 for(
size_t i=0; 
i<mapRes.data.nodes.size(); ++
i)
 
  215                 ROS_INFO(
"Added %d/%d nodes to memory! Vocabulary size=%d",
 
  217                                 (
int)mapRes.data.nodes.size(),
 
  226                 ROS_INFO(
"Set detector in localization mode");
 
  232         infoTopic.
subscribe(nh, 
"/rtabmap/info", 1);
 
  233         mapDataTopic.
subscribe(nh, 
"/rtabmap/mapData", 1);
 
  
std::pair< std::string, std::string > ParametersPair
rtabmap::Signature nodeFromROS(const rtabmap_msgs::Node &msg)
const Signature & getLastSignatureData() const
GLenum const GLfloat * params
void uncompressDataConst(cv::Mat *imageRaw, cv::Mat *depthOrRightRaw, LaserScan *laserScanRaw=0, cv::Mat *userDataRaw=0, cv::Mat *groundCellsRaw=0, cv::Mat *obstacleCellsRaw=0, cv::Mat *emptyCellsRaw=0) const
message_filters::sync_policies::ExactTime< rtabmap_msgs::MapData, rtabmap_msgs::Info > MyInfoMapSyncPolicy
ros::ServiceClient addLinkSrv
const std::map< int, VisualWord * > & getVisualWords() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
const Memory * getMemory() const
void mapGraphFromROS(const rtabmap_msgs::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom)
static void setLevel(ULogger::Level level)
Transform computeTransformation(const SensorData &from, const SensorData &to, Transform guess=Transform::getIdentity(), RegistrationInfo *info=0) const
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ROSCPP_DECL void spinOnce()
void mapDataCallback(const rtabmap_msgs::MapDataConstPtr &mapDataMsg, const rtabmap_msgs::InfoConstPtr &infoMsg)
int getLoopClosureId() const
void linkToROS(const rtabmap::Link &link, rtabmap_msgs::Link &msg)
std::map< std::string, std::string > ParametersMap
std::string getTopic() const
Connection registerCallback(C &callback)
const Statistics & getStatistics() const
void infoFromROS(const rtabmap_msgs::Info &info, rtabmap::Statistics &stat)
ros::ServiceClient getMapSrv
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
rtabmap::RegistrationVis reg
void init(const ParametersMap ¶meters, const std::string &databasePath="", bool loadDatabaseParameters=false)
int main(int argc, char **argv)
bool process(const cv::Mat &image, int id=0, const std::map< std::string, float > &externalStats=std::map< std::string, float >())
void parseParameters(const ParametersMap ¶meters)
std::map< int, rtabmap::SensorData > localData
const VWDictionary * getVWDictionary() const
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
T param(const std::string ¶m_name, const T &default_val) const
rtabmap::Rtabmap loopClosureDetector
void mapDataFromROS(const rtabmap_msgs::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
rtabmap_examples
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:51:35