51 std::string merged_map_topic;
59 private_nh.
param<std::string>(
"robot_map_updates_topic",
62 private_nh.
param<std::string>(
"merged_map_topic", merged_map_topic,
"map");
67 node_.
advertise<nav_msgs::OccupancyGrid>(merged_map_topic, 50,
true);
78 geometry_msgs::Transform init_pose;
79 std::string robot_name;
80 std::string map_topic;
81 std::string map_updates_topic;
85 init_pose.rotation.w = 1;
87 for (
const auto& topic : topic_infos) {
94 if (
robots_.count(robot_name)) {
100 ROS_WARN(
"Couldn't get initial position for robot [%s]\n" 101 "did you defined parameters map_merge/init_pose_[xyz]? in robot " 102 "namespace? If you want to run merging without known initial " 103 "positions of robots please set `known_init_poses` parameter " 104 "to false. See relavant documentation for details.",
109 ROS_INFO(
"adding robot [%s] to system", robot_name.c_str());
118 robots_.insert({robot_name, &subscription});
125 ROS_INFO(
"Subscribing to MAP topic: %s.", map_topic.c_str());
128 [
this, &subscription](
const nav_msgs::OccupancyGrid::ConstPtr& msg) {
131 ROS_INFO(
"Subscribing to MAP updates topic: %s.",
132 map_updates_topic.c_str());
135 map_updates_topic, 50,
136 [
this, &subscription](
137 const map_msgs::OccupancyGridUpdate::ConstPtr& msg) {
151 std::vector<nav_msgs::OccupancyGridConstPtr> grids;
152 std::vector<geometry_msgs::Transform> transforms;
157 std::lock_guard<std::mutex> s_lock(subscription.mutex);
158 grids.push_back(subscription.readonly_map);
159 transforms.push_back(subscription.initial_pose);
168 nav_msgs::OccupancyGridPtr merged_map;
177 ROS_DEBUG(
"all maps merged, publishing");
179 merged_map->info.map_load_time = now;
180 merged_map->header.stamp = now;
187 ROS_DEBUG(
"Grid pose estimation started.");
188 std::vector<nav_msgs::OccupancyGridConstPtr> grids;
193 std::lock_guard<std::mutex> s_lock(subscription.mutex);
194 grids.push_back(subscription.readonly_map);
207 std::lock_guard<std::mutex> lock(subscription.
mutex);
209 subscription.
readonly_map->header.stamp > msg->header.stamp) {
219 const map_msgs::OccupancyGridUpdate::ConstPtr& msg,
222 ROS_DEBUG(
"received partial map update");
224 if (msg->x < 0 || msg->y < 0) {
225 ROS_ERROR(
"negative coordinates, invalid update. x: %d, y: %d", msg->x,
230 size_t x0 =
static_cast<size_t>(msg->x);
231 size_t y0 =
static_cast<size_t>(msg->y);
232 size_t xn = msg->width + x0;
233 size_t yn = msg->height + y0;
235 nav_msgs::OccupancyGridPtr map;
236 nav_msgs::OccupancyGridConstPtr readonly_map;
239 std::lock_guard<std::mutex> lock(subscription.
mutex);
245 ROS_WARN(
"received partial map update, but don't have any full map to " 246 "update. skipping.");
253 map.reset(
new nav_msgs::OccupancyGrid(*readonly_map));
256 size_t grid_xn = map->info.width;
257 size_t grid_yn = map->info.height;
259 if (xn > grid_xn || x0 > grid_xn || yn > grid_yn || y0 > grid_yn) {
260 ROS_WARN(
"received update doesn't fully fit into existing map, " 261 "only part will be copied. received: [%lu, %lu], [%lu, %lu] " 262 "map is: [0, %lu], [0, %lu]",
263 x0, xn, y0, yn, grid_xn, grid_yn);
268 for (
size_t y = y0; y < yn && y < grid_yn; ++y) {
269 for (
size_t x = x0; x < xn && x < grid_xn; ++x) {
270 size_t idx = y * grid_xn + x;
271 map->data[idx] = msg->data[i];
276 map->header.stamp = msg->header.stamp;
280 std::lock_guard<std::mutex> lock(subscription.
mutex);
282 subscription.
readonly_map->header.stamp > map->header.stamp) {
306 bool contains_robot_namespace = pos != std::string::npos;
309 bool is_occupancy_grid = topic.
datatype ==
"nav_msgs/OccupancyGrid";
314 return is_occupancy_grid && !is_our_topic && contains_robot_namespace &&
322 geometry_msgs::Transform& pose)
329 pose.translation.x) &&
331 pose.translation.y) &&
333 pose.translation.z) &&
339 pose.rotation =
toMsg(q);
387 estimation_thr.join();
389 subscribing_thr.join();
394 int main(
int argc,
char** argv)
bool getInitPose(const std::string &name, geometry_msgs::Transform &pose)
combine_grids::MergingPipeline pipeline_
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
void publish(const boost::shared_ptr< M > &message) const
std::string robotNameFromTopic(const std::string &topic)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
nav_msgs::OccupancyGrid::Ptr composeGrids()
ROSCPP_DECL std::string parentNamespace(const std::string &name)
size_t subscriptions_size_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
std::unordered_map< std::string, MapSubscription * > robots_
ROSCPP_DECL bool getTopics(V_TopicInfo &topics)
std::string robot_map_updates_topic_
std::vector< TopicInfo > V_TopicInfo
ros::Subscriber map_updates_sub
ROSCPP_DECL void spin(Spinner &spinner)
bool estimateTransforms(FeatureType feature=FeatureType::AKAZE, double confidence=1.0)
std::forward_list< MapSubscription > subscriptions_
std::string robot_namespace_
nav_msgs::OccupancyGrid::ConstPtr readonly_map
ROSCPP_DECL bool get(const std::string &key, std::string &s)
void executeposeEstimation()
void partialMapUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr &msg, MapSubscription &map)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
bool setTransforms(InputIt transforms_begin, InputIt transforms_end)
bool isRobotMapTopic(const ros::master::TopicInfo &topic)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
geometry_msgs::Transform initial_pose
void setEuler(const tf2Scalar &yaw, const tf2Scalar &pitch, const tf2Scalar &roll)
std::string robot_map_topic_
double confidence_treshold_
nav_msgs::OccupancyGrid::Ptr writable_map
void feed(InputIt grids_begin, InputIt grids_end)
int main(int argc, char **argv)
ROSCPP_DECL std::string append(const std::string &left, const std::string &right)
ros::Publisher merged_map_publisher_
boost::shared_mutex subscriptions_mutex_
void poseEstimation()
Estimates initial positions of grids.
std::string getTopic() const
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
void fullMapUpdate(const nav_msgs::OccupancyGrid::ConstPtr &msg, MapSubscription &map)
ROSCPP_DECL void spinOnce()
std::mutex pipeline_mutex_
#define ROSCONSOLE_DEFAULT_NAME
void executetopicSubscribing()