29 #include <ros/publisher.h> 32 #include <rtabmap_ros/MapData.h> 33 #include <rtabmap_ros/Info.h> 35 #include <rtabmap_ros/AddLink.h> 36 #include <rtabmap_ros/GetMap.h> 74 void mapDataCallback(
const rtabmap_ros::MapDataConstPtr & mapDataMsg,
const rtabmap_ros::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;
107 if(loopClosureDetector.
process(rgb,
id))
113 ROS_INFO(
"Detected loop closure between %d and %d", fromId, toId);
127 rtabmap_ros::AddLinkRequest req;
129 rtabmap_ros::AddLinkResponse
res;
130 if(!addLinkSrv.
call(req, 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)
155 ros::init(argc, argv,
"external_loop_detection_example");
166 loopClosureDetector.
init(params,
"");
171 addLinkSrv = nh.
serviceClient<rtabmap_ros::AddLink>(
"/rtabmap/add_link");
174 getMapSrv = nh.
serviceClient<rtabmap_ros::GetMap>(
"/rtabmap/get_map_data");
176 rtabmap_ros::GetMap::Request mapReq;
177 mapReq.global =
true;
178 mapReq.graphOnly =
false;
179 mapReq.optimized =
false;
180 rtabmap_ros::GetMap::Response mapRes;
182 while(!getMapSrv.exists() && nh.
ok())
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());
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())
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);
ros::ServiceClient getMapSrv
message_filters::sync_policies::ExactTime< rtabmap_ros::MapData, rtabmap_ros::Info > MyInfoMapSyncPolicy
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
int main(int argc, char **argv)
rtabmap::Signature nodeDataFromROS(const rtabmap_ros::NodeData &msg)
rtabmap::RegistrationVis reg
std::string getTopic() const
const Statistics & getStatistics() const
std::pair< std::string, std::string > ParametersPair
std::map< int, rtabmap::SensorData > localData
Transform computeTransformation(const Signature &from, const Signature &to, Transform guess=Transform::getIdentity(), RegistrationInfo *info=0) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
std::map< std::string, std::string > ParametersMap
void init(const ParametersMap ¶meters, const std::string &databasePath="", bool loadDatabaseParameters=false)
const std::map< int, VisualWord *> & getVisualWords() const
static void setLevel(ULogger::Level level)
geometry_msgs::TransformStamped t
const std::map< std::string, float > & data() const
rtabmap::Rtabmap loopClosureDetector
void mapDataCallback(const rtabmap_ros::MapDataConstPtr &mapDataMsg, const rtabmap_ros::InfoConstPtr &infoMsg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void mapDataFromROS(const rtabmap_ros::MapData &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, std::map< int, rtabmap::Signature > &signatures, rtabmap::Transform &mapToOdom)
Connection registerCallback(C &callback)
void linkToROS(const rtabmap::Link &link, rtabmap_ros::Link &msg)
const Memory * getMemory() const
void infoFromROS(const rtabmap_ros::Info &info, rtabmap::Statistics &stat)
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
void mapGraphFromROS(const rtabmap_ros::MapGraph &msg, std::map< int, rtabmap::Transform > &poses, std::multimap< int, rtabmap::Link > &links, rtabmap::Transform &mapToOdom)
bool process(const SensorData &data, Transform odomPose, const cv::Mat &odomCovariance=cv::Mat::eye(6, 6, CV_64FC1), const std::vector< float > &odomVelocity=std::vector< float >(), const std::map< std::string, float > &externalStats=std::map< std::string, float >())
void parseParameters(const ParametersMap ¶meters)
ros::ServiceClient addLinkSrv
SensorData & sensorData()
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
const Signature & getLastSignatureData() const
ROSCPP_DECL void spinOnce()
const VWDictionary * getVWDictionary() const
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
V uValue(const std::map< K, V > &m, const K &key, const V &defaultValue=V())
int getLoopClosureId() const