26 ROS_INFO(
"MergeMapsKinematic: Starting up!");
37 "/map_metadata", 1,
true));
43 tfB_ = std::make_unique<tf2_ros::TransformBroadcaster>();
46 std::make_unique<interactive_markers::InteractiveMarkerServer>(
47 "merge_maps_tool",
"",
true);
58 slam_toolbox_msgs::AddSubmap::Request& req,
59 slam_toolbox_msgs::AddSubmap::Response& resp)
62 std::unique_ptr<karto::Mapper> mapper = std::make_unique<karto::Mapper>();
63 std::unique_ptr<karto::Dataset> dataset = std::make_unique<karto::Dataset>();
67 ROS_ERROR(
"addSubmapCallback: Failed to read "
68 "file: %s.", req.filename.c_str());
74 dataset->GetLasers()[0]);
75 dataset->Add(laser,
true);
92 "/map_metadata_" + std::to_string(
num_submaps_), 1,
true));
95 nav_msgs::GetMap::Response map;
96 nav_msgs::OccupancyGrid& og = map.map;
102 ROS_WARN(
"Failed to build grid to add submap, Exception: %s",
109 transform.
setOrigin(tf2::Vector3(og.info.origin.position.x +
110 og.info.width * og.info.resolution / 2.0,
111 og.info.origin.position.y + og.info.height * og.info.resolution / 2.0,
113 og.info.origin.position.x = - (og.info.width * og.info.resolution / 2.0);
114 og.info.origin.position.y = - (og.info.height * og.info.resolution / 2.0);
116 og.header.frame_id =
"map_"+std::to_string(
num_submaps_);
120 geometry_msgs::TransformStamped msg;
122 msg.child_frame_id =
"/map_"+std::to_string(
num_submaps_);
123 msg.header.frame_id =
"/map";
125 tfB_->sendTransform(msg);
129 tf2::Vector3(0,0,0));
131 Eigen::Vector3d(transform.
getOrigin().getX(),
135 visualization_msgs::Marker m =
137 m.pose.position.x = transform.
getOrigin().getX();
138 m.pose.position.y = transform.
getOrigin().getY();
141 visualization_msgs::InteractiveMarker int_marker =
147 ROS_INFO(
"Map %s was loaded into topic %s!", req.filename.c_str(),
163 pose_corr = submap_correction * pose_tf;
177 pose_corr = submap_correction * pose_tf;
188 const karto::Pose2 bary_center_pose = (*iter)->GetBarycenterPose();
189 auto bary_center_pose_corr =
191 (*iter)->SetBarycenterPose(bary_center_pose_corr);
201 (*iter)->SetBoundingBox(bbox);
205 for(karto::PointVectorDouble::iterator it_upr = UPR_vec.begin();
206 it_upr != UPR_vec.end(); ++it_upr)
209 *it_upr, submap_correction);
210 it_upr->SetX(upr_corr.
GetX());
211 it_upr->SetY(upr_corr.
GetY());
213 (*iter)->SetPointReadings(UPR_vec);
216 const karto::Pose2 corrected_pose = (*iter)->GetCorrectedPose();
218 corrected_pose, submap_correction);
219 (*iter)->SetCorrectedPose(karto_robot_pose_corr);
221 (*iter)->SetIsDirty(dirty);
226 odom_pose, submap_correction);
227 (*iter)->SetOdometricPose(karto_robot_pose_odom);
232 slam_toolbox_msgs::MergeMaps::Request& req,
233 slam_toolbox_msgs::MergeMaps::Response& resp)
246 iter != it_LRV->end(); ++iter)
250 transformed_scans.push_back((*iter));
255 nav_msgs::GetMap::Response map;
261 ROS_WARN(
"Failed to build grid to merge maps together, Exception: %s",
267 map.map.header.frame_id =
"map";
268 sstS_[0].publish(map.map);
269 sstmS_[0].publish(map.map.info);
276 nav_msgs::GetMap::Response& map)
283 ROS_INFO(
"MergeMapsKinematic: Could not make Karto occupancy grid.");
297 visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
300 const int id = std::stoi(feedback->marker_name,
nullptr,10);
302 if (feedback->event_type ==
303 visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP &&
304 feedback->mouse_point_valid)
317 feedback->pose.position.y,
326 geometry_msgs::TransformStamped msg;
328 msg.child_frame_id =
"/map_"+std::to_string(
id);
329 msg.header.frame_id =
"/map";
331 tfB_->sendTransform(msg);
334 previous_submap_correction.
inverse() * new_submap_location;
337 if (feedback->event_type ==
338 visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE)
346 new_submap_location.
setOrigin(tf2::Vector3(feedback->pose.position.x,
347 feedback->pose.position.y, 0.));
350 geometry_msgs::TransformStamped msg;
352 msg.child_frame_id =
"/map_"+std::to_string(
id);
353 msg.header.frame_id =
"/map";
355 tfB_->sendTransform(msg);
360 int main(
int argc,
char** argv)
363 ros::init(argc, argv,
"merge_maps_kinematic");