diff --git a/launch/3d_nav_nomap.launch b/launch/3d_nav_nomap.launch index 963c57ae8c8551c5670baf2bf9a9ff1c1b3f16d6..3cbb3cd296fe85aa4f661ea0f4abed33e4b308a5 100644 --- a/launch/3d_nav_nomap.launch +++ b/launch/3d_nav_nomap.launch @@ -5,7 +5,7 @@ <arg name="name" default="ana"/> <arg name="use_3d_nav_nodelets" default="true"/> - <arg name="nav_camera" default="nav_cam_top"/> + <arg name="nav_camera" default="nav_cam"/> <arg name="path" default="$(find iri_ana_rosnav)/params"/> <arg name="move_base_params" default="move_base_params.yaml"/> diff --git a/params/move_base_params.yaml b/params/move_base_params.yaml index aa2617cc87ad0e02b5230460302df13923745d1c..4cc23ae3a785b681a233bba388bc89b4c885803f 100644 --- a/params/move_base_params.yaml +++ b/params/move_base_params.yaml @@ -25,5 +25,5 @@ clearing_rotation_allowed: false clearing_radius: 0.46 shutdown_costmaps: false -oscillation_timeout: 4.0 -oscillation_distance: 0.2 +oscillation_timeout: 0.0 +oscillation_distance: 0.0