ExternalLoopDetectionExample.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <ros/ros.h>
29 #include <ros/publisher.h>
30 #include <ros/subscriber.h>
31 
32 #include <rtabmap_msgs/MapData.h>
33 #include <rtabmap_msgs/Info.h>
35 #include <rtabmap_msgs/AddLink.h>
36 #include <rtabmap_msgs/GetMap.h>
37 
38 #include <rtabmap/core/Rtabmap.h>
39 #include <rtabmap/core/Memory.h>
41 #include <rtabmap/core/util3d.h>
43 #include <rtabmap/utilite/UStl.h>
44 
48 
49 /*
50  * Test:
51  * $ roslaunch rtabmap_demos demo_robot_mapping.launch
52  * Disable internal loop closure detection, in rtabmapviz->Preferences:
53  * ->Vocabulary, set Max words to -1 (loop closure detection disabled)
54  * ->Proximity Detection, uncheck proximity detection by space
55  * $ rosrun rtabmap_examples external_loop_detection_example
56  * $ rosbag play --clock demo_mapping.bag
57  */
58 
60 
63 
64 // This is used to keep in cache the old data of the map
65 std::map<int, rtabmap::SensorData> localData;
66 
67 // In this example, we use rtabmap for our loop closure detector
69 
71 
72 bool g_localizationMode = false;
73 
74 void mapDataCallback(const rtabmap_msgs::MapDataConstPtr & mapDataMsg, const rtabmap_msgs::InfoConstPtr & infoMsg)
75 {
76  ROS_INFO("Received map data!");
77 
80 
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);
83 
84  if(smallMovement || fastMovement)
85  {
86  // The signature has been ignored from rtabmap, don't process it
87  return;
88  }
89 
90  rtabmap::Transform mapToOdom;
91  std::map<int, rtabmap::Transform> poses;
92  std::multimap<int, rtabmap::Link> links;
93  std::map<int, rtabmap::Signature> signatures;
94  rtabmap_conversions::mapDataFromROS(*mapDataMsg, poses, links, signatures, mapToOdom);
95 
96  if(!signatures.empty() &&
97  signatures.rbegin()->second.sensorData().isValid() &&
98  localData.find(signatures.rbegin()->first) == localData.end())
99  {
100  int id = signatures.rbegin()->first;
101  const rtabmap::SensorData & s = signatures.rbegin()->second.sensorData();
102  cv::Mat rgb;
103  //rtabmap::LaserScan scan;
104  s.uncompressDataConst(&rgb, 0/*, &scan*/);
105  //pcl::PointCloud<pcl::PointXYZ>::Ptr cloud = rtabmap::util3d::laserScanToPointCloud(scan, scan.localTransform());
106 
107  if(loopClosureDetector.process(rgb, id))
108  {
110  {
111  int fromId = id;
113  ROS_INFO("Detected loop closure between %d and %d", fromId, toId);
114  if(localData.find(toId) != localData.end())
115  {
116  //Compute transformation
118  rtabmap::SensorData tmpFrom = s;
119  rtabmap::SensorData tmpTo = localData.at(toId);
120  tmpFrom.uncompressData();
121  tmpTo.uncompressData();
122  rtabmap::Transform t = reg.computeTransformation(tmpFrom, tmpTo, rtabmap::Transform(), &regInfo);
123 
124  if(!t.isNull())
125  {
126  rtabmap::Link link(fromId, toId, rtabmap::Link::kUserClosure, t, regInfo.covariance.inv());
127  rtabmap_msgs::AddLinkRequest req;
128  rtabmap_conversions::linkToROS(link, req.link);
129  rtabmap_msgs::AddLinkResponse res;
130  if(!addLinkSrv.call(req, res))
131  {
132  ROS_ERROR("Failed to call %s service", addLinkSrv.getService().c_str());
133  }
134  }
135  else
136  {
137  ROS_WARN("Could not compute transformation between %d and %d: %s", fromId, toId, regInfo.rejectedMsg.c_str());
138  }
139  }
140  else
141  {
142  ROS_WARN("Could not compute transformation between %d and %d because node data %d is not in cache.", fromId, toId, toId);
143  }
144  }
145  if(!g_localizationMode)
146  {
147  localData.insert(std::make_pair(id, s));
148  }
149  }
150  }
151 }
152 
153 int main(int argc, char** argv)
154 {
155  ros::init(argc, argv, "external_loop_detection_example");
156 
159 
160  ros::NodeHandle nh;
161  ros::NodeHandle pnh("~");
162 
164  params.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemGenerateIds(), "false")); // use provided ids
165  params.insert(rtabmap::ParametersPair(rtabmap::Parameters::kRGBDEnabled(), "false")); // BOW-only mode
167 
168  pnh.param("localization", g_localizationMode, g_localizationMode);
169 
170  // service to add link
171  addLinkSrv = nh.serviceClient<rtabmap_msgs::AddLink>("/rtabmap/add_link");
172 
173  // service to get map for initialization
174  getMapSrv = nh.serviceClient<rtabmap_msgs::GetMap>("/rtabmap/get_map_data");
175 
176  rtabmap_msgs::GetMap::Request mapReq;
177  mapReq.global = true;
178  mapReq.graphOnly = false;
179  mapReq.optimized = false;
180  rtabmap_msgs::GetMap::Response mapRes;
181  ros::Rate rate(1);
182  while(!getMapSrv.exists() && nh.ok())
183  {
184  ROS_INFO("Waiting for service \"%s\" to be available. If rtabmap is already started, "
185  "make sure the service name is the same or remap it.", getMapSrv.getService().c_str());
186  rate.sleep();
187  ros::spinOnce();
188  }
189  if(!nh.ok())
190  {
191  return 0;
192  }
193  ROS_INFO("Calling \"%s\" service to get data already in the map.", getMapSrv.getService().c_str());
194  if(getMapSrv.call(mapReq, mapRes) && !mapRes.data.nodes.empty())
195  {
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;
199  rtabmap::Transform mapToOdom;
200  rtabmap_conversions::mapGraphFromROS(mapRes.data.graph, poses, links, mapToOdom);
201  int addedNodes = 0;
202  for(size_t i=0; i<mapRes.data.nodes.size(); ++i)
203  {
204  rtabmap::Signature s = rtabmap_conversions::nodeFromROS(mapRes.data.nodes.at(i));
205  rtabmap::SensorData compressedData = s.sensorData();
206  s.sensorData().uncompressData();
207  if(loopClosureDetector.process(s.sensorData(), rtabmap::Transform()))
208  {
209  localData.insert(std::make_pair(
211  compressedData));
212  ++addedNodes;
213  }
214  }
215  ROS_INFO("Added %d/%d nodes to memory! Vocabulary size=%d",
216  addedNodes,
217  (int)mapRes.data.nodes.size(),
219 
220  }
221 
223  {
224  params.insert(rtabmap::ParametersPair(rtabmap::Parameters::kMemIncrementalMemory(), "false")); // localization mode
226  ROS_INFO("Set detector in localization mode");
227  }
228 
229  // subscription
232  infoTopic.subscribe(nh, "/rtabmap/info", 1);
233  mapDataTopic.subscribe(nh, "/rtabmap/mapData", 1);
236  mapDataTopic,
237  infoTopic);
238  infoMapSync.registerCallback(&mapDataCallback);
239  ROS_INFO("Subscribed to %s and %s", mapDataTopic.getTopic().c_str(), infoTopic.getTopic().c_str());
240 
241  ros::spin();
242 
243  return 0;
244 }
rtabmap::SensorData
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
rtabmap_conversions::nodeFromROS
rtabmap::Signature nodeFromROS(const rtabmap_msgs::Node &msg)
rtabmap::SensorData::uncompressData
void uncompressData()
rtabmap::Statistics::getLastSignatureData
const Signature & getLastSignatureData() const
rtabmap::Statistics
params
GLenum const GLfloat * params
rtabmap::SensorData::uncompressDataConst
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::Synchronizer
MyInfoMapSyncPolicy
message_filters::sync_policies::ExactTime< rtabmap_msgs::MapData, rtabmap_msgs::Info > MyInfoMapSyncPolicy
Definition: ExternalLoopDetectionExample.cpp:59
addLinkSrv
ros::ServiceClient addLinkSrv
Definition: ExternalLoopDetectionExample.cpp:61
rtabmap::VWDictionary::getVisualWords
const std::map< int, VisualWord * > & getVisualWords() const
ros::ServiceClient::exists
bool exists()
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
rtabmap::Rtabmap::getMemory
const Memory * getMemory() const
rtabmap::RegistrationInfo
ULogger::kTypeConsole
kTypeConsole
ros.h
rtabmap_conversions::mapGraphFromROS
void mapGraphFromROS(const rtabmap_msgs::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom)
ULogger::setLevel
static void setLevel(ULogger::Level level)
rtabmap::Registration::computeTransformation
Transform computeTransformation(const SensorData &from, const SensorData &to, Transform guess=Transform::getIdentity(), RegistrationInfo *info=0) const
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::spinOnce
ROSCPP_DECL void spinOnce()
UStl.h
Rtabmap.h
mapDataCallback
void mapDataCallback(const rtabmap_msgs::MapDataConstPtr &mapDataMsg, const rtabmap_msgs::InfoConstPtr &infoMsg)
Definition: ExternalLoopDetectionExample.cpp:74
rtabmap::Rtabmap::getLoopClosureId
int getLoopClosureId() const
rtabmap_conversions::linkToROS
void linkToROS(const rtabmap::Link &link, rtabmap_msgs::Link &msg)
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
message_filters::Subscriber::getTopic
std::string getTopic() const
message_filters::Subscriber< rtabmap_msgs::Info >
message_filters::Synchronizer::registerCallback
Connection registerCallback(C &callback)
id
void * id
rtabmap::Rtabmap::getStatistics
const Statistics & getStatistics() const
ros::ServiceClient::getService
std::string getService()
stats
bool stats
RegistrationVis.h
argv
argv
VWDictionary.h
rtabmap::RegistrationVis
subscriber.h
ULogger::kWarning
kWarning
rtabmap::RegistrationInfo::rejectedMsg
std::string rejectedMsg
rtabmap_conversions::infoFromROS
void infoFromROS(const rtabmap_msgs::Info &info, rtabmap::Statistics &stat)
rtabmap::RegistrationInfo::covariance
cv::Mat covariance
ROS_ERROR
#define ROS_ERROR(...)
res
GLuint res
ros::ServiceClient
ROS_WARN
#define ROS_WARN(...)
getMapSrv
ros::ServiceClient getMapSrv
Definition: ExternalLoopDetectionExample.cpp:62
uValue
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
ULogger::setType
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
reg
rtabmap::RegistrationVis reg
Definition: ExternalLoopDetectionExample.cpp:70
rate
GLuint GLenum * rate
rtabmap::Rtabmap::init
void init(const ParametersMap &parameters, const std::string &databasePath="", bool loadDatabaseParameters=false)
main
int main(int argc, char **argv)
Definition: ExternalLoopDetectionExample.cpp:153
exact_time.h
message_filters::Subscriber::subscribe
void subscribe()
rtabmap::Transform
ros::NodeHandle::ok
bool ok() const
rtabmap::Signature::id
int id() const
rtabmap::Rtabmap::process
bool process(const cv::Mat &image, int id=0, const std::map< std::string, float > &externalStats=std::map< std::string, float >())
t
GLdouble t
rtabmap::Rtabmap::parseParameters
void parseParameters(const ParametersMap &parameters)
localData
std::map< int, rtabmap::SensorData > localData
Definition: ExternalLoopDetectionExample.cpp:65
rtabmap::Memory::getVWDictionary
const VWDictionary * getVWDictionary() const
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
synchronizer.h
loopClosureDetector
rtabmap::Rtabmap loopClosureDetector
Definition: ExternalLoopDetectionExample.cpp:68
ros::Rate
ros::spin
ROSCPP_DECL void spin()
rtabmap::Rtabmap
rtabmap_conversions::mapDataFromROS
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)
message_filters::sync_policies::ExactTime
Memory.h
ROS_INFO
#define ROS_INFO(...)
MsgConversion.h
s
GLdouble s
g_localizationMode
bool g_localizationMode
Definition: ExternalLoopDetectionExample.cpp:72
i
int i
util3d.h
ros::NodeHandle
rtabmap::Signature


rtabmap_examples
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:51:35