Skip to content

Commit

Permalink
Reverting some of the default naming parameters to match existing
Browse files Browse the repository at this point in the history
  • Loading branch information
TirelessDev committed Jan 18, 2023
1 parent f9c893d commit c514939
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 13 deletions.
4 changes: 2 additions & 2 deletions apps/hdl_graph_slam_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ class HdlGraphSlamNodelet : public nodelet::Nodelet {
private_nh = getPrivateNodeHandle();

// init parameters
published_odom_topic = private_nh.param<std::string>("published_odom_topic", "/hdl_graph_slam/odom");
published_odom_topic = private_nh.param<std::string>("published_odom_topic", "/odom");
map_frame_id = private_nh.param<std::string>("map_frame_id", "map");
odom_frame_id = private_nh.param<std::string>("odom_frame_id", "odom");
map_cloud_resolution = private_nh.param<double>("map_cloud_resolution", 0.05);
Expand Down Expand Up @@ -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();
Expand Down
2 changes: 1 addition & 1 deletion apps/scan_matching_odometry_nodelet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ class ScanMatchingOdometryNodelet : public nodelet::Nodelet {
*/
void initialize_params() {
auto& pnh = private_nh;
published_odom_topic = private_nh.param<std::string>("published_odom_topic", "/hdl_graph_slam/odom");
published_odom_topic = private_nh.param<std::string>("published_odom_topic", "/odom");
points_topic = pnh.param<std::string>("points_topic", "/velodyne_points");
odom_frame_id = pnh.param<std::string>("odom_frame_id", "odom");
robot_odom_frame_id = pnh.param<std::string>("robot_odom_frame_id", "robot_odom");
Expand Down
14 changes: 7 additions & 7 deletions launch/hdl_graph_slam.launch
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
<?xml version="1.0"?>
<launch>
<!-- arguments -->
<arg name="nodelet_manager" default="hdl_graph_slam_nodelet_manager" />
<arg name="enable_floor_detection" default="true" />
<arg name="enable_gps" default="true" />
<arg name="nodelet_manager" default="velodyne_nodelet_manager" />
<arg name="enable_floor_detection" default="false" />
<arg name="enable_gps" default="false" />
<arg name="enable_imu_acc" default="false" />
<arg name="enable_imu_ori" default="false" />

Expand All @@ -13,15 +13,15 @@
<!-- topic for hdl to find velodyne points -->
<arg name="points_topic" default="/velodyne_points" />
<!-- what should the map frame be called -->
<arg name="map_frame_id" default="slam_map" />
<arg name="map_frame_id" default="map" />
<!-- what should the base link frame be called -->
<arg name="base_link_frame_id" default="slam_base_link" />
<arg name="base_link_frame_id" default="base_link" />
<!-- what should the odom frame be called -->
<arg name="lidar_odom_frame_id" default="slam_odom" />
<arg name="lidar_odom_frame_id" default="odom" />

<!-- hdl_graph_slam will also publish an odom message -->
<!-- what should the topic be for odom messages published by hdl-graph-slam -->
<arg name="published_odom_topic" default="/hdl_graph_slam/odom" />
<arg name="published_odom_topic" default="/odom" />

<!-- optional arguments -->
<arg name="enable_robot_odometry_init_guess" default="false" />
Expand Down
6 changes: 3 additions & 3 deletions src/hdl_graph_slam/map2odom_publisher.py
Original file line number Diff line number Diff line change
Expand Up @@ -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()
Expand Down Expand Up @@ -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)

Expand Down

0 comments on commit c514939

Please sign in to comment.