diff --git a/apps/hdl_graph_slam_nodelet.cpp b/apps/hdl_graph_slam_nodelet.cpp index 92bb3236..1579280c 100644 --- a/apps/hdl_graph_slam_nodelet.cpp +++ b/apps/hdl_graph_slam_nodelet.cpp @@ -76,7 +76,7 @@ class HdlGraphSlamNodelet : public nodelet::Nodelet { private_nh = getPrivateNodeHandle(); // init parameters - published_odom_topic = private_nh.param("published_odom_topic", "/hdl_graph_slam/odom"); + published_odom_topic = private_nh.param("published_odom_topic", "/odom"); map_frame_id = private_nh.param("map_frame_id", "map"); odom_frame_id = private_nh.param("odom_frame_id", "odom"); map_cloud_resolution = private_nh.param("map_cloud_resolution", 0.05); @@ -826,7 +826,7 @@ class HdlGraphSlamNodelet : public nodelet::Nodelet { graph_slam->load(directory + "/graph.g2o"); // Load keyframes by looping through key frame indexes that we expect to see. - for(int i = 0; i < 1000; i++) { // un magic this max iterator + for(int i = 0; i < 10000; i++) { // un magic this max iterator std::stringstream sst; sst << boost::format("%s/%06d") % directory % i; std::string keyframeDir = sst.str(); diff --git a/apps/scan_matching_odometry_nodelet.cpp b/apps/scan_matching_odometry_nodelet.cpp index b880d68a..d1118829 100644 --- a/apps/scan_matching_odometry_nodelet.cpp +++ b/apps/scan_matching_odometry_nodelet.cpp @@ -64,7 +64,7 @@ class ScanMatchingOdometryNodelet : public nodelet::Nodelet { */ void initialize_params() { auto& pnh = private_nh; - published_odom_topic = private_nh.param("published_odom_topic", "/hdl_graph_slam/odom"); + published_odom_topic = private_nh.param("published_odom_topic", "/odom"); points_topic = pnh.param("points_topic", "/velodyne_points"); odom_frame_id = pnh.param("odom_frame_id", "odom"); robot_odom_frame_id = pnh.param("robot_odom_frame_id", "robot_odom"); diff --git a/launch/hdl_graph_slam.launch b/launch/hdl_graph_slam.launch index a4fea6c0..92923fb9 100644 --- a/launch/hdl_graph_slam.launch +++ b/launch/hdl_graph_slam.launch @@ -1,9 +1,9 @@ - - - + + + @@ -13,15 +13,15 @@ - + - + - + - + diff --git a/src/hdl_graph_slam/map2odom_publisher.py b/src/hdl_graph_slam/map2odom_publisher.py index 6dd7d736..14da7bb8 100755 --- a/src/hdl_graph_slam/map2odom_publisher.py +++ b/src/hdl_graph_slam/map2odom_publisher.py @@ -6,7 +6,7 @@ class Map2OdomPublisher: - def __init__(self, odom_frame_id = 'slam_odom', map_frame_id = 'slam_map'): + def __init__(self, odom_frame_id = 'odom', map_frame_id = 'map'): self.default_odom_frame_id = odom_frame_id self.default_map_frame_id = map_frame_id self.broadcaster = tf.TransformBroadcaster() @@ -34,8 +34,8 @@ def main(): rospy.init_node('map2odom_publisher') # get some parameters to define what default frame_id's should be used while we wait for our first odom message - map_frame_id = rospy.get_param('~map_frame_id', 'slam_map') - odom_frame_id = rospy.get_param('~odom_frame_id', 'slam_odom') + map_frame_id = rospy.get_param('~map_frame_id', 'map') + odom_frame_id = rospy.get_param('~odom_frame_id', 'odom') node = Map2OdomPublisher(odom_frame_id, map_frame_id)