diff --git a/src/navigation_stack/launch/move_base.launch b/src/navigation_stack/launch/move_base.launch
index 79b6463..2621a7e 100644
--- a/src/navigation_stack/launch/move_base.launch
+++ b/src/navigation_stack/launch/move_base.launch
@@ -2,33 +2,46 @@
-
-
-
-
-
-
-
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
-
-
-
-
+
+
-
-
-
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/src/navigation_stack/params/costmap_common_params.yaml b/src/navigation_stack/params/costmap_common_params.yaml
index 46ff87f..9961e97 100644
--- a/src/navigation_stack/params/costmap_common_params.yaml
+++ b/src/navigation_stack/params/costmap_common_params.yaml
@@ -23,8 +23,8 @@ obstacle_layer:
combination_method: 1
observation_sources: laser_scan_sensor
- laser_scan_sensor: {sensor_frame: base_scan, data_type: LaserScan,
- topic: top/scan, marking: true, clearing: true}
+ laser_scan_sensor: {sensor_frame: base_laser_link, data_type: LaserScan,
+ topic: /sim_stage/scan, marking: true, clearing: true}
#point_cloud_sensor: {sensor_frame: velodyne, data_type: PointCloud2,
# topic: velodyne_points, marking: true, clearing: true}
@@ -35,4 +35,4 @@ inflation_layer:
static_layer:
enabled: true
- map_topic: "map"
+ map_topic: "/map"
diff --git a/src/navigation_stack/params/teb_local_planner_params.yaml b/src/navigation_stack/params/teb_local_planner_params.yaml
index 27e87a3..891aea8 100644
--- a/src/navigation_stack/params/teb_local_planner_params.yaml
+++ b/src/navigation_stack/params/teb_local_planner_params.yaml
@@ -4,7 +4,7 @@
# TODO(Issue 25): Ensure these params work for both simulation and match the
# kart's physical params.
TebLocalPlannerROS:
- odom_topic: "odom"
+ odom_topic: "/sim_stage/odom"
# Trajectory
teb_autosize: True
diff --git a/src/rtabmap_manager/launch/rtabmap_manager.launch b/src/rtabmap_manager/launch/rtabmap_manager.launch
index 9c65295..14b22b6 100644
--- a/src/rtabmap_manager/launch/rtabmap_manager.launch
+++ b/src/rtabmap_manager/launch/rtabmap_manager.launch
@@ -1,12 +1,13 @@
-
+
-
-
-
-
+
+
+
+
+
@@ -22,7 +23,7 @@
-
+
@@ -37,7 +38,7 @@
-
+
diff --git a/src/rtabmap_manager/params/rtabmap.yaml b/src/rtabmap_manager/params/rtabmap.yaml
index fce4a17..4db850c 100644
--- a/src/rtabmap_manager/params/rtabmap.yaml
+++ b/src/rtabmap_manager/params/rtabmap.yaml
@@ -14,7 +14,7 @@ config_path: "~/.ros/rtabmap.cfg"
frame_id: "base_link"
map_frame_id: "map"
-odom_frame_id: "odom" # odometry from odom msg to have covariance - Remapped by launch file
+odom_frame_id: "odom" # Odometry is taken from TF.
odom_tf_angular_variance: 0.001 # If TF is used to get odometry, this is the default angular variance
odom_tf_linear_variance: 0.001 # If TF is used to get odometry, this is the default linear variance
tf_delay: 0.02
diff --git a/src/sim_stage/launch/stage.launch b/src/sim_stage/launch/stage.launch
index c7de532..22b2364 100644
--- a/src/sim_stage/launch/stage.launch
+++ b/src/sim_stage/launch/stage.launch
@@ -6,6 +6,16 @@
+
+
+
+
+
+
+
+
+
+
-
-
-
-
-
-
-
-
-
-
-
-
-
-
+
+
+
+
+
+
+
+
+
+
-
-
-
-
+
+
+
+
+
+
+
+
+
+ output="screen" args="$(arg lidar_scan_topic)" />
-
+
+
+
+
+
+