29 #include "rtabmap_ros/MapData.h" 30 #include "rtabmap_ros/MapGraph.h" 40 #include <ros/publisher.h> 42 #include <boost/thread.hpp> 53 globalOptimization_(
true),
54 optimizeFromLastNode_(
false),
66 bool ignoreVariance =
false;
68 pnh.
param(
"map_frame_id", mapFrameId_, mapFrameId_);
69 pnh.
param(
"odom_frame_id", odomFrameId_, odomFrameId_);
70 pnh.
param(
"iterations", iterations, iterations);
71 pnh.
param(
"ignore_variance", ignoreVariance, ignoreVariance);
72 pnh.
param(
"global_optimization", globalOptimization_, globalOptimization_);
73 pnh.
param(
"optimize_from_last_node", optimizeFromLastNode_, optimizeFromLastNode_);
74 pnh.
param(
"epsilon", epsilon, epsilon);
75 pnh.
param(
"robust", robust, robust);
76 pnh.
param(
"slam_2d", slam2d, slam2d);
77 pnh.
param(
"strategy", strategy, strategy);
91 double tfDelay = 0.05;
92 bool publishTf =
true;
93 pnh.
param(
"publish_tf", publishTf, publishTf);
94 pnh.
param(
"tf_delay", tfDelay, tfDelay);
98 mapGraphPub_ = nh.
advertise<rtabmap_ros::MapGraph>(nh.
resolveName(
"mapData")+
"Graph_optimized", 1);
102 ROS_INFO(
"map_optimizer will publish tf between frames \"%s\" and \"%s\"", mapFrameId_.c_str(), odomFrameId_.c_str());
103 ROS_INFO(
"map_optimizer: map_frame_id = %s", mapFrameId_.c_str());
104 ROS_INFO(
"map_optimizer: odom_frame_id = %s", odomFrameId_.c_str());
105 ROS_INFO(
"map_optimizer: tf_delay = %f", tfDelay);
114 transformThread_->join();
115 delete transformThread_;
126 mapToOdomMutex_.lock();
129 msg.child_frame_id = odomFrameId_;
130 msg.header.frame_id = mapFrameId_;
131 msg.header.stamp = tfExpiration;
133 tfBroadcaster_.sendTransform(msg);
134 mapToOdomMutex_.unlock();
143 UASSERT(msg->graph.posesId.size() == msg->graph.poses.size());
145 bool dataChanged =
false;
147 std::multimap<int, Link> newConstraints;
148 for(
unsigned int i=0; i<msg->graph.links.size(); ++i)
151 newConstraints.insert(std::make_pair(link.
from(), link));
153 bool edgeAlreadyAdded =
false;
154 for(std::multimap<int, Link>::iterator iter = cachedConstraints_.lower_bound(link.
from());
155 iter != cachedConstraints_.end() && iter->first == link.
from();
158 if(iter->second.to() == link.
to())
160 edgeAlreadyAdded =
true;
161 if(iter->second.transform().getDistanceSquared(link.
transform()) > 0.0001)
163 ROS_WARN(
"%d ->%d (%s vs %s)",iter->second.from(), iter->second.to(), iter->second.transform().prettyPrint().c_str(),
169 if(!edgeAlreadyAdded)
171 cachedConstraints_.insert(std::make_pair(link.
from(), link));
175 std::map<int, Signature> newNodeInfos;
177 for(
unsigned int i=0; i<msg->nodes.size(); ++i)
179 int id = msg->nodes[i].id;
182 newNodeInfos.insert(std::make_pair(
id, s));
184 std::pair<std::map<int, Signature>::iterator,
bool> p = cachedNodeInfos_.insert(std::make_pair(
id, s));
193 ROS_WARN(
"Graph data has changed! Reset cache...");
194 cachedConstraints_ = newConstraints;
195 cachedNodeInfos_ = newNodeInfos;
199 std::multimap<int, Link> constraints;
200 std::map<int, Signature> nodeInfos;
201 if(globalOptimization_)
203 constraints = cachedConstraints_;
204 nodeInfos = cachedNodeInfos_;
208 constraints = newConstraints;
209 for(
unsigned int i=0; i<msg->graph.posesId.size(); ++i)
211 std::map<int, Signature>::iterator iter = cachedNodeInfos_.find(msg->graph.posesId[i]);
212 if(iter != cachedNodeInfos_.end())
214 nodeInfos.insert(*iter);
218 ROS_ERROR(
"Odometry pose of node %d not found in cache!", msg->graph.posesId[i]);
224 std::map<int, Transform> poses;
225 for(std::map<int, Signature>::iterator iter=nodeInfos.begin(); iter!=nodeInfos.end(); ++iter)
227 poses.insert(std::make_pair(iter->first, iter->second.getPose()));
231 if(mapDataPub_.getNumSubscribers() || mapGraphPub_.getNumSubscribers())
234 std::map<int, Transform> optimizedPoses;
236 std::map<int, rtabmap::Transform> posesOut;
237 std::multimap<int, rtabmap::Link> linksOut;
238 if(poses.size() > 1 && constraints.size() > 0)
240 int fromId = optimizeFromLastNode_?poses.rbegin()->first:poses.begin()->first;
241 optimizer_->getConnectedGraph(
247 optimizedPoses = optimizer_->optimize(fromId, posesOut, linksOut);
248 mapToOdomMutex_.lock();
249 mapCorrection = optimizedPoses.at(posesOut.rbegin()->first) * posesOut.rbegin()->second.
inverse();
250 mapToOdom_ = mapCorrection;
251 mapToOdomMutex_.unlock();
253 else if(poses.size() == 1 && constraints.size() == 0)
255 optimizedPoses = poses;
257 else if(poses.size() == 0 && constraints.size())
259 ROS_ERROR(
"map_optimizer: Poses=%d and edges=%d: poses must " 260 "not be null if there are edges.",
261 (
int)poses.size(), (int)constraints.size());
264 rtabmap_ros::MapData outputDataMsg;
265 rtabmap_ros::MapGraph outputGraphMsg;
271 if(mapGraphPub_.getNumSubscribers())
273 outputGraphMsg.header = msg->header;
274 mapGraphPub_.publish(outputGraphMsg);
277 if(mapDataPub_.getNumSubscribers())
279 outputDataMsg.header = msg->header;
280 outputDataMsg.graph = outputGraphMsg;
281 outputDataMsg.nodes = msg->nodes;
282 if(posesOut.size() > msg->nodes.size())
284 std::set<int> addedNodes;
285 for(
unsigned int i=0; i<msg->nodes.size(); ++i)
287 addedNodes.insert(msg->nodes[i].id);
289 std::list<int> toAdd;
290 for(std::map<int, Transform>::iterator iter=posesOut.begin(); iter!=posesOut.end(); ++iter)
292 if(addedNodes.find(iter->first) == addedNodes.end())
294 toAdd.push_back(iter->first);
299 int oi = outputDataMsg.nodes.size();
300 outputDataMsg.nodes.resize(outputDataMsg.nodes.size()+toAdd.size());
301 for(std::list<int>::iterator iter=toAdd.begin(); iter!=toAdd.end(); ++iter)
303 UASSERT(cachedNodeInfos_.find(*iter) != cachedNodeInfos_.end());
309 mapDataPub_.publish(outputDataMsg);
339 int main(
int argc,
char** argv)
void mapDataReceivedCallback(const rtabmap_ros::MapDataConstPtr &msg)
rtabmap::Transform mapToOdom_
void mapGraphToROS(const std::map< int, rtabmap::Transform > &poses, const std::multimap< int, rtabmap::Link > &links, const rtabmap::Transform &mapToOdom, rtabmap_ros::MapGraph &msg)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::pair< std::string, std::string > ParametersPair
std::string resolveName(const std::string &name, bool remap=true) const
boost::mutex mapToOdomMutex_
void transformToGeometryMsg(const rtabmap::Transform &transform, geometry_msgs::Transform &msg)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
rtabmap::Signature nodeInfoFromROS(const rtabmap_ros::NodeData &msg)
std::string uBool2Str(bool boolean)
const Transform & transform() const
ROSCPP_DECL void spin(Spinner &spinner)
#define UASSERT(condition)
boost::thread * transformThread_
std::string uNumber2Str(unsigned int number)
ros::Publisher mapGraphPub_
std::multimap< int, Link > cachedConstraints_
GLM_FUNC_DECL genType epsilon()
rtabmap::Link linkFromROS(const rtabmap_ros::Link &msg)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
int main(int argc, char **argv)
ros::Subscriber mapDataTopic_
QMap< QString, QVariant > ParametersMap
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
rtabmap::Transform transformFromPoseMsg(const geometry_msgs::Pose &msg)
tf2_ros::TransformBroadcaster tfBroadcaster_
void publishLoop(double tfDelay)
ros::Publisher mapDataPub_
bool optimizeFromLastNode_
void nodeDataToROS(const rtabmap::Signature &signature, rtabmap_ros::NodeData &msg)
static Optimizer * create(const ParametersMap ¶meters)
std::map< int, Signature > cachedNodeInfos_