Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
15 changes: 10 additions & 5 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -8,8 +8,13 @@ and without any URDF models. However, they are easily extendable and integrable

Refer to the [teb_local_planner](http://wiki.ros.org/teb_local_planner) ROS wiki page for more information.

**Dependencies:**

* *navigation stack* and *teb_local_planner* package
* *stage*: `sudo apt-get install ros-kinetic-stage-ros`

# Using
(Tested OK on ubuntu 18.04 LTS + ros-melodic)
- install *navigation stack* and *teb_local_planner* package
- Build [**fixed stage_ros**](https://github.com/AMRobots/stage_ros):
```
$ git clone https://github.com/AMRobots/stage_ros.git
$ cd ../
$ catkin_make --only-pkg-with-deps stage_ros
$ source devel/setup.bash
```
248 changes: 112 additions & 136 deletions launch/dyn_obst_corridor_scenario.launch
Original file line number Diff line number Diff line change
@@ -1,136 +1,112 @@
<launch>
<arg name="map_file" default="corridor"/>

<!-- ************** Global Parameters *************** -->
<param name="/use_sim_time" value="true"/>

<!-- ************** Stage Simulator ***************** -->
<node pkg="stage_ros" type="stageros" name="stageros" args="$(find teb_local_planner_tutorials)/stage/$(arg map_file).world">
<remap from="/robot_0/base_scan" to="/robot_0/scan"/>
</node>

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

<!-- ************** Navigation ROBOT 0 ************* -->
<group ns="robot_0">
<!-- 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="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" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/local_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/global_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/teb_local_planner_params.yaml" command="load" />
<!-- Here we load our costmap conversion settings -->
<!-- If you active the following line, disable 'ground_truth_obstacles' at the bottom of this script! -->
<!-- rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/costmap_converter_params.yaml" command="load" /-->
<param name="TebLocalPlannerROS/include_costmap_obstacles" value="False" />
<param name="TebLocalPlannerROS/include_dynamic_obstacles" value="True" />

<param name="base_global_planner" value="navfn/NavfnROS" />
<!--param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="planner_frequency" value="1.0" />
<param name="planner_patience" value="5.0" /-->

<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
<param name="controller_frequency" value="5.0" />
<param name="controller_patience" value="15.0" />
<remap from="map" to="/map"/>
</node>
</group>

<!-- ****************** Obstacles ******************** -->
<group ns="robot_1">
<param name="tf_prefix" value="robot_1"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_2">
<param name="tf_prefix" value="robot_2"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_3">
<param name="tf_prefix" value="robot_3"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_4">
<param name="tf_prefix" value="robot_4"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_5">
<param name="tf_prefix" value="robot_5"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_6">
<param name="tf_prefix" value="robot_6"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_7">
<param name="tf_prefix" value="robot_7"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_8">
<param name="tf_prefix" value="robot_8"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_9">
<param name="tf_prefix" value="robot_9"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_10">
<param name="tf_prefix" value="robot_10"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_11">
<param name="tf_prefix" value="robot_11"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_12">
<param name="tf_prefix" value="robot_12"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<group ns="robot_13">
<param name="tf_prefix" value="robot_13"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>

<node name="ground_truth_obstacles" pkg="teb_local_planner_tutorials" type="publish_ground_truth_obstacles.py" output="screen" />

<!--node name="visualize_velocity_profile" pkg="teb_local_planner_tutorials" type="visualize_velocity_profile.py" output="screen" /-->

<!-- **************** Visualisation **************** -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find teb_local_planner_tutorials)/cfg/rviz_navigation_cc.rviz">
<remap from="/move_base_simple/goal" to="/robot_0/move_base_simple/goal" />
</node>

</launch>
<?xml version="1.0" encoding="UTF-8"?>
<launch>
<arg name="map_file" default="corridor"/>
<!-- ************** Global Parameters *************** -->
<param name="/use_sim_time" value="true"/>
<!-- ************** Stage Simulator ***************** -->
<node pkg="stage_ros" type="stageros" name="stageros" args="$(find teb_local_planner_tutorials)/stage/$(arg map_file).world">
<remap from="/robot_0/base_scan" to="/robot_0/scan"/>
</node>
<!-- ******************* Maps *********************** -->
<node name="map_server" pkg="map_server" type="map_server" args="$(find teb_local_planner_tutorials)/maps/$(arg map_file).yaml" output="screen">
<param name="frame_id" value="map"/>
</node>
<!-- ************** Navigation ROBOT 0 ************* -->
<group ns="robot_0">
<!-- work around for footprint reload -->
<rosparam command="delete" ns="move_base" />
<node pkg="tf" type="static_transform_publisher" name="link1_broadcaster" args="0 0 0 0 0 0 /map /robot_0/odom 100" />
<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" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/costmap_common_params.yaml" command="load" ns="local_costmap" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/local_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/global_costmap_params.yaml" command="load" />
<rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/teb_local_planner_params.yaml" command="load" />
<!-- Here we load our costmap conversion settings -->
<!-- If you active the following line, disable 'ground_truth_obstacles' at the bottom of this script! -->
<!-- rosparam file="$(find teb_local_planner_tutorials)/cfg/diff_drive/dyn_obst/costmap_converter_params.yaml" command="load" /-->
<param name="TebLocalPlannerROS/include_costmap_obstacles" value="False" />
<param name="TebLocalPlannerROS/include_dynamic_obstacles" value="True" />
<param name="base_global_planner" value="navfn/NavfnROS" />
<!--param name="base_global_planner" value="global_planner/GlobalPlanner" />
<param name="planner_frequency" value="1.0" />
<param name="planner_patience" value="5.0" /-->
<param name="base_local_planner" value="teb_local_planner/TebLocalPlannerROS" />
<param name="controller_frequency" value="5.0" />
<param name="controller_patience" value="15.0" />
<remap from="map" to="/map"/>
</node>
</group>
<!-- ****************** Obstacles ******************** -->
<group ns="robot_1">
<param name="tf_prefix" value="robot_1"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_2">
<param name="tf_prefix" value="robot_2"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_3">
<param name="tf_prefix" value="robot_3"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_4">
<param name="tf_prefix" value="robot_4"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_5">
<param name="tf_prefix" value="robot_5"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_6">
<param name="tf_prefix" value="robot_6"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_7">
<param name="tf_prefix" value="robot_7"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_8">
<param name="tf_prefix" value="robot_8"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_9">
<param name="tf_prefix" value="robot_9"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_10">
<param name="tf_prefix" value="robot_10"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_11">
<param name="tf_prefix" value="robot_11"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_12">
<param name="tf_prefix" value="robot_12"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<group ns="robot_13">
<param name="tf_prefix" value="robot_13"/>
<node name="Mover" pkg="teb_local_planner_tutorials" type="move_obstacle.py" output="screen"/>
<param name="vel_y" value="0.3" />
</group>
<node name="ground_truth_obstacles" pkg="teb_local_planner_tutorials" type="publish_ground_truth_obstacles.py" output="screen" />
<!--node name="visualize_velocity_profile" pkg="teb_local_planner_tutorials" type="visualize_velocity_profile.py" output="screen" /-->
<!-- **************** Visualisation **************** -->
<node name="rviz" pkg="rviz" type="rviz" args="-d $(find teb_local_planner_tutorials)/cfg/rviz_navigation_cc.rviz">
<remap from="/move_base_simple/goal" to="/robot_0/move_base_simple/goal" />
</node>
</launch>