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);
275 nav_msgs::GetMap::Response& map)
282 ROS_INFO(
"MergeMapsKinematic: Could not make Karto occupancy grid.");
296 visualization_msgs::InteractiveMarkerFeedbackConstPtr& feedback)
299 const int id = std::stoi(feedback->marker_name,
nullptr,10);
301 if (feedback->event_type ==
302 visualization_msgs::InteractiveMarkerFeedback::MOUSE_UP &&
303 feedback->mouse_point_valid)
316 feedback->pose.position.y,
325 geometry_msgs::TransformStamped msg;
327 msg.child_frame_id =
"/map_"+std::to_string(
id);
328 msg.header.frame_id =
"/map";
330 tfB_->sendTransform(msg);
333 previous_submap_correction.
inverse() * new_submap_location;
336 if (feedback->event_type ==
337 visualization_msgs::InteractiveMarkerFeedback::POSE_UPDATE)
345 new_submap_location.
setOrigin(tf2::Vector3(feedback->pose.position.x,
346 feedback->pose.position.y, 0.));
349 geometry_msgs::TransformStamped msg;
351 msg.child_frame_id =
"/map_"+std::to_string(
id);
352 msg.header.frame_id =
"/map";
354 tfB_->sendTransform(msg);
359 int main(
int argc,
char** argv)
362 ros::init(argc, argv,
"merge_maps_kinematic");
void processInteractiveFeedback(const visualization_msgs::InteractiveMarkerFeedbackConstPtr &feedback)
void setRPY(const tf2Scalar &roll, const tf2Scalar &pitch, const tf2Scalar &yaw)
ros::ServiceServer ssSubmap_
void SetMinimum(const Vector2< kt_double > &mMinimum)
int main(int argc, char **argv)
std::vector< karto::LocalizedRangeScanVector >::iterator LocalizedRangeScansVecIt
std::vector< Vector2< kt_double > > PointVectorDouble
std::map< int, tf2::Transform > submap_marker_transform_
std::unique_ptr< tf2_ros::TransformBroadcaster > tfB_
void transformScan(LocalizedRangeScansIt iter, tf2::Transform &submap_correction)
karto::Pose2 applyCorrection(const karto::Pose2 &pose, const tf2::Transform &submap_correction)
void kartoToROSOccupancyGrid(const karto::LocalizedRangeScanVector &scans, nav_msgs::GetMap::Response &map)
void toNavMap(const karto::OccupancyGrid *occ_grid, nav_msgs::OccupancyGrid &map)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool read(const std::string &filename, karto::Mapper &mapper, karto::Dataset &dataset)
const std::string & GetName() const
bool addSubmapCallback(slam_toolbox_msgs::AddSubmap::Request &req, slam_toolbox_msgs::AddSubmap::Response &resp)
std::map< std::string, laser_utils::LaserMetadata > lasers_
std::vector< ros::Publisher > sstmS_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
karto::LocalizedRangeScanVector::iterator LocalizedRangeScansIt
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::ServiceServer ssMap_
static OccupancyGrid * CreateFromScans(const LocalizedRangeScanVector &rScans, kt_double resolution)
double getYaw(const A &a)
visualization_msgs::Marker toMarker(const std::string &frame, const std::string &ns, const double &scale)
const Name & GetName() const
std::vector< std::unique_ptr< karto::Dataset > > dataset_vec_
visualization_msgs::InteractiveMarker toInteractiveMarker(visualization_msgs::Marker &marker, const double &scale)
void convert(const A &a, B &b)
const Vector2< kt_double > & GetMinimum() const
void SetMaximum(const Vector2< kt_double > &rMaximum)
std::vector< karto::LocalizedRangeScanVector > scans_vec_
const Vector2< kt_double > & GetMaximum() const
const std::string & GetErrorMessage() const
std::unique_ptr< interactive_markers::InteractiveMarkerServer > interactive_server_
bool mergeMapCallback(slam_toolbox_msgs::MergeMaps::Request &req, slam_toolbox_msgs::MergeMaps::Response &resp)
std::map< int, Eigen::Vector3d > submap_locations_
std::vector< LocalizedRangeScan * > LocalizedRangeScanVector
std::vector< ros::Publisher > sstS_
kt_double GetHeading() const