Skip to content

Commit

Permalink
remove trailing slashes from frame names. Multiple robot/obstacle set…
Browse files Browse the repository at this point in the history
…up with stage not yet working. See ros-simulation/stage_ros#40
  • Loading branch information
croesmann committed Aug 7, 2018
1 parent 67f96a0 commit 8793c53
Show file tree
Hide file tree
Showing 17 changed files with 20 additions and 23 deletions.
2 changes: 1 addition & 1 deletion cfg/amcl_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ use_map_topic: true

odom_frame_id: "odom"
base_frame_id: "base_footprint"
global_frame_id: "/map"
global_frame_id: "map"

## Publish scans from best pose at a max of 10 Hz
odom_model_type: "diff"
Expand Down
2 changes: 1 addition & 1 deletion cfg/carlike/costmap_common_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -27,4 +27,4 @@ inflation_layer:

static_layer:
enabled: true
map_topic: "/map"
map_topic: "map"
2 changes: 1 addition & 1 deletion cfg/carlike/global_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
global_costmap:
global_frame: /map
global_frame: map
robot_base_frame: base_link
update_frequency: 1.0
publish_frequency: 0.5
Expand Down
2 changes: 1 addition & 1 deletion cfg/carlike/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
local_costmap:
global_frame: /map
global_frame: map
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
Expand Down
5 changes: 4 additions & 1 deletion cfg/diff_drive/costmap_common_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,9 @@
robot_radius: 0.17
footprint_padding: 0.00

global_frame: map
robot_base_frame: robot_0/base_link

transform_tolerance: 0.2
map_type: costmap

Expand All @@ -28,4 +31,4 @@ inflation_layer:

static_layer:
enabled: true
map_topic: "/map"
map_topic: map
2 changes: 0 additions & 2 deletions cfg/diff_drive/dyn_obst/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
local_costmap:
global_frame: /map
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 5.001 # actually exactly 5.0Hz, see https://github.com/ros-planning/navigation/issues/383
static_map: false
Expand Down
2 changes: 0 additions & 2 deletions cfg/diff_drive/global_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
global_costmap:
global_frame: /map
robot_base_frame: base_link
update_frequency: 1.0
publish_frequency: 0.5
static_map: true
Expand Down
2 changes: 0 additions & 2 deletions cfg/diff_drive/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,6 +1,4 @@
local_costmap:
global_frame: /map
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
static_map: false
Expand Down
2 changes: 1 addition & 1 deletion cfg/omnidir/costmap_common_params.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -26,4 +26,4 @@ inflation_layer:

static_layer:
enabled: true
map_topic: "/map"
map_topic: "map"
2 changes: 1 addition & 1 deletion cfg/omnidir/global_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
global_costmap:
global_frame: /map
global_frame: map
robot_base_frame: base_link
update_frequency: 1.0
publish_frequency: 0.5
Expand Down
2 changes: 1 addition & 1 deletion cfg/omnidir/local_costmap_params.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
local_costmap:
global_frame: /map
global_frame: map
robot_base_frame: base_link
update_frequency: 5.0
publish_frequency: 2.0
Expand Down
2 changes: 1 addition & 1 deletion launch/dyn_obst_corridor_scenario.launch
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
<!-- work around for footprint reload -->
<rosparam command="delete" ns="move_base" />

<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="2 3 0 0 0 0 1 /map /robot_0/odom 100" />
<node pkg="tf2_ros" type="static_transform_publisher" name="link1_broadcaster" args="2 3 0 0 0 0 1 map robot_0/odom" />

<node pkg="move_base" type="move_base" respawn="false" name="move_base" output="screen">
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/costmap_common_params.yaml" command="load" ns="global_costmap" />
Expand Down
8 changes: 4 additions & 4 deletions launch/dyn_obst_costmap_conversion.launch
Original file line number Diff line number Diff line change
Expand Up @@ -16,12 +16,12 @@

<!-- ******** Localization ********* -->
<!-- See stage world file for initial poses -->
<node pkg="tf" type="static_transform_publisher" name="perfect_loc_robot" args="-2 0 0 -1.570796 0 0 /map robot_0/odom 100" />
<node pkg="tf" type="static_transform_publisher" name="perfect_loc_obstacle" args="0 1 0 0 0 0 /map robot_1/odom 100" />
<node pkg="tf2_ros" type="static_transform_publisher" name="perfect_loc_robot" args="-2 0 0 -1.570796 0 0 map robot_0/odom" />
<node pkg="tf2_ros" type="static_transform_publisher" name="perfect_loc_obstacle" args="0 1 0 0 0 0 map robot_1/odom" />

<!-- ************* Navigation Ego Robot ************ -->
<!-- ************* Navigation Ego Robot ************ -->
<group ns="robot_0">
<param name="tf_prefix" value="robot_0"/>
<!--param name="tf_prefix" value="robot_0"/-->
<!-- work around for footprint reload -->
<rosparam command="delete" ns="move_base" />

Expand Down
2 changes: 1 addition & 1 deletion launch/robot_carlike_in_stage.launch
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@

<!-- ****** Maps ***** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find teb_local_planner_tutorials)/maps/maze.yaml" output="screen">
<param name="frame_id" value="/map"/>
<param name="frame_id" value="map"/>
</node>

<node pkg="amcl" type="amcl" name="amcl" output="screen">
Expand Down
2 changes: 1 addition & 1 deletion launch/robot_diff_drive_in_stage.launch
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@

<!-- ****** Maps ***** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find teb_local_planner_tutorials)/maps/maze.yaml" output="screen">
<param name="frame_id" value="/map"/>
<param name="frame_id" value="map"/>
</node>

<node pkg="amcl" type="amcl" name="amcl" output="screen">
Expand Down
2 changes: 1 addition & 1 deletion launch/robot_diff_drive_in_stage_costmap_conversion.launch
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@

<!-- ****** Maps ***** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find teb_local_planner_tutorials)/maps/maze.yaml" output="screen">
<param name="frame_id" value="/map"/>
<param name="frame_id" value="map"/>
</node>

<node pkg="amcl" type="amcl" name="amcl" output="screen">
Expand Down
2 changes: 1 addition & 1 deletion launch/robot_omnidir_in_stage.launch
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@

<!-- ****** Maps ***** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find teb_local_planner_tutorials)/maps/maze.yaml" output="screen">
<param name="frame_id" value="/map"/>
<param name="frame_id" value="map"/>
</node>

<node pkg="amcl" type="amcl" name="amcl" output="screen">
Expand Down

0 comments on commit 8793c53

Please sign in to comment.