diff --git a/launch/include/map_server.launch b/launch/include/map_server.launch index ab694e3a171248543ad3094b990fbefebfb8f7bc..d1530600fe4d648623cbd14f2281b2e911589882 100644 --- a/launch/include/map_server.launch +++ b/launch/include/map_server.launch @@ -3,7 +3,7 @@ <launch> <arg name="ns" default="robot"/> - <arg name="map_path" default="$(find iri_maps)/maps/"/> + <arg name="map_path" default="$(find iri_maps)/maps"/> <arg name="map_name" default="empty"/> <arg name="map_frame_id" default="map"/> <arg name="map_topic" default="$(arg ns)/map"/> diff --git a/launch/nav.launch b/launch/nav.launch index 07e8de2e487489edfc5a1cff5de35b7c75895ac4..1e3dafec33b45481bb3e96b377ed016e5e963ae3 100644 --- a/launch/nav.launch +++ b/launch/nav.launch @@ -82,13 +82,15 @@ </group> </group> - <group unless="$(arg use_map)"> - <node pkg="tf" - type="static_transform_publisher" - name="static_tf_map" - ns="$(arg ns)" - args=" 0 0 0 0 0 0 $(arg map_frame_id) $(arg odom_frame_id) 100"> - </node> + <group unless="$(arg use_fake_loc)"> + <group unless="$(arg use_map)"> + <node pkg="tf" + type="static_transform_publisher" + name="static_tf_map" + ns="$(arg ns)" + args=" 0 0 0 0 0 0 $(arg map_frame_id) $(arg odom_frame_id) 100"> + </node> + </group> </group> <group if="$(arg use_fake_loc)"> diff --git a/params/local_planner/dwa_params.yaml b/params/local_planner/dwa_params.yaml index 3d67331832cbed5747cb66bb1f4bf854e78f3891..3e6db94582565fb567627d8349219ca9654c1e5b 100644 --- a/params/local_planner/dwa_params.yaml +++ b/params/local_planner/dwa_params.yaml @@ -3,19 +3,19 @@ latch_xy_goal_tolerance: true DWAPlannerROS: # robot configuration parameters - max_trans_vel: 0.5 - min_trans_vel: 0.1 + max_vel_trans: 0.5 + min_vel_trans: 0.1 max_vel_x: 0.5 min_vel_x: -0.5 max_vel_y: 0.0 min_vel_y: 0.0 - max_rot_vel: 0.5 - min_rot_vel: 0.0 + max_vel_theta: 0.5 + min_vel_theta: 0.0 acc_lim_theta: 3.0 acc_lim_x: 1.0 acc_lim_y: 0.0 - acc_limit_trans: 1.0 - rot_stopped_vel: 0.1 + acc_lim_trans: 1.0 + theta_stopped_vel: 0.1 trans_stopped_vel: 0.1 # goal tolerance parameters