From ca97029cb6b5fb2d39fa976a8c6f77cf6f4a33c6 Mon Sep 17 00:00:00 2001
From: fherrero <fherrero@iri.upc.edu>
Date: Mon, 25 Feb 2019 17:03:09 +0100
Subject: [PATCH] Add generic nav parameters, fix fake_loc launch remaps

---
 launch/include/fake_loc.launch                |  6 +-
 launch/nav.launch                             | 20 +++++--
 params/{amcl_default.yaml => amcl.yaml}       |  6 +-
 params/costmap/common_params.yaml             | 59 +++++++++++++++++++
 params/costmap/local_params.yaml              | 15 +++++
 params/costmap/map/global_params.yaml         | 21 +++++++
 params/costmap/no_map/global_params.yaml      | 15 +++++
 .../global_planner/global_planner_params.yaml | 22 +++++++
 .../{gmapping_default.yaml => gmapping.yaml}  |  0
 params/local_planner/dwa_params.yaml          | 54 +++++++++++++++++
 params/move_base_params.yaml                  | 23 ++++++++
 params/{cmdvelmux_default.yaml => mux.yaml}   |  0
 12 files changed, 231 insertions(+), 10 deletions(-)
 rename params/{amcl_default.yaml => amcl.yaml} (91%)
 create mode 100644 params/costmap/common_params.yaml
 create mode 100644 params/costmap/local_params.yaml
 create mode 100644 params/costmap/map/global_params.yaml
 create mode 100644 params/costmap/no_map/global_params.yaml
 create mode 100644 params/global_planner/global_planner_params.yaml
 rename params/{gmapping_default.yaml => gmapping.yaml} (100%)
 create mode 100644 params/local_planner/dwa_params.yaml
 create mode 100644 params/move_base_params.yaml
 rename params/{cmdvelmux_default.yaml => mux.yaml} (100%)

diff --git a/launch/include/fake_loc.launch b/launch/include/fake_loc.launch
index 0078bff..a5e22d0 100644
--- a/launch/include/fake_loc.launch
+++ b/launch/include/fake_loc.launch
@@ -30,9 +30,9 @@
       <param name="delta_x"             value="$(arg initial_x)" />
       <param name="delta_y"             value="$(arg initial_y)" />
       <param name="delta_yaw"           value="$(arg initial_yaw)" />
-      <remap from="/odom"                  to="$(arg odom_topic)"/>
-      <remap from="base_pose_ground_truth" to="$(arg ground_truth_topic)"/>
-      <remap from="initialpose"            to="$(arg initialpose_topic)"/>
+      <remap from="/odom"                  to="/$(arg odom_topic)"/>
+      <remap from="base_pose_ground_truth" to="/$(arg ground_truth_topic)"/>
+      <remap from="initialpose"            to="/$(arg initialpose_topic)"/>
     </node>
     
   </group>
diff --git a/launch/nav.launch b/launch/nav.launch
index f80c230..61c0284 100644
--- a/launch/nav.launch
+++ b/launch/nav.launch
@@ -15,18 +15,18 @@
   <arg name="use_map_server" default="true"/>
     <arg name="map_name"       default="willow"/>
   <arg name="use_amcl"       default="true"/>
-    <arg name="amcl_config"    default="$(arg path)/params/amcl_default.yaml"/>
+    <arg name="amcl_config"    default="$(arg path)/params/amcl.yaml"/>
     <arg name="initial_x"      default="0.0"/>
     <arg name="initial_y"      default="0.0"/>
     <arg name="initial_yaw"    default="0.0"/>
   <arg name="use_fake_loc"   default="false"/>
   <arg name="use_gmapping"   default="false"/>
     <arg name="gmapping_scan_topic"     default="/$(arg ns)/front_hokuyo_scan"/>
-    <arg name="gmapping_config" default="$(arg path)/params/gmapping_default.yaml"/>
+    <arg name="gmapping_config" default="$(arg path)/params/gmapping.yaml"/>
     <arg name="resolution"     default="0.1"/>
   <arg name="use_cmd_vel_mux"      default="false"/>
     <arg name="nodelet_manager_name" default="nodelet_manager"/>
-    <arg name="cmd_vel_mux_config"   default="$(arg path)/params/cmdvelmux_default.yaml"/>
+    <arg name="cmd_vel_mux_config"   default="$(arg path)/params/mux.yaml"/>
   <arg name="use_move_base"  default="true"/>
     <arg name="local_planner"  default="dwa"/>
     <arg name="global_planner" default="global_planner"/>
@@ -62,7 +62,7 @@
         <arg name="launch_prefix" value="$(arg launch_prefix)" />
       </include>
     </group>
-    
+
     <group if="$(arg use_gmapping)">
       <include file="$(find iri_rosnav)/launch/include/gmapping.launch">
         <arg name="ns"            value="$(arg ns)"/>
@@ -79,6 +79,17 @@
     </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>
+
   <group if="$(arg use_fake_loc)"> 
     <include file="$(find iri_rosnav)/launch/include/fake_loc.launch">
       <arg name="ns"            value="$(arg ns)"/>
@@ -89,6 +100,7 @@
       <arg name="initial_y"     value="$(arg initial_y)"/>
       <arg name="initial_yaw"   value="$(arg initial_yaw)"/>
       <arg name="odom_topic"    value="$(arg odom_topic)"/>
+      <arg name="ground_truth_topic" value="$(arg odom_topic)"/>
       <arg name="output"        value="$(arg output)" />
       <arg name="launch_prefix" value="$(arg launch_prefix)" />
     </include>
diff --git a/params/amcl_default.yaml b/params/amcl.yaml
similarity index 91%
rename from params/amcl_default.yaml
rename to params/amcl.yaml
index 027ace2..66df324 100644
--- a/params/amcl_default.yaml
+++ b/params/amcl.yaml
@@ -1,6 +1,6 @@
-#map_frame_id: map
-#odom_frame_id: odom
-#base_frame_id: base_link
+map_frame_id: map
+odom_frame_id: robot/odom
+base_frame_id: robot/base_footprint
 initial_x: 0.0
 initial_y: 0.0
 initial_a: 0.0
diff --git a/params/costmap/common_params.yaml b/params/costmap/common_params.yaml
new file mode 100644
index 0000000..d059da1
--- /dev/null
+++ b/params/costmap/common_params.yaml
@@ -0,0 +1,59 @@
+# footprint parameters
+#footprint: [[0.35, 0.35], [0.35, -0.35], [-0.35,-0.35 ], [-0.35, 0.35]]
+robot_radius: 0.5
+footprint_padding: -0.1
+footprint_topic: /robot/move_base/local_costmap/footprint
+published_footprint_topic: false
+
+robot_base_frame: /robot/base_footprint
+track_unknown_space: false
+always_send_full_costmap: false
+transform_tolerance: 1.0
+width: 10.0
+height: 10.0
+resolution: 0.1
+origin_x: 0.0
+origin_y: 0.0
+
+obstacle_layer:
+  enabled: true
+  track_unknown_space: true
+  transform_tolerance: 0.2
+  max_obstacle_height: 1.0
+  footprint_clearing_enabled: false
+  combination_method: 1
+  observation_sources: front_laser rear_laser
+  front_laser:  {
+    sensor_frame: /robot/front_hokuyo_scan_frame,
+    data_type: LaserScan,
+    topic: /robot/sensors/front_scan,
+    observation_persistence: 0.0,
+    marking: true,
+    clearing: true,
+    min_obstacle_height: 0.05,
+    max_obstacle_height: 1.8,
+    expected_update_rate: 10,
+    obstacle_range: 30.0,
+    raytrace_range: 40.0
+  }
+  
+  rear_laser:  {
+    sensor_frame: /robot/rear_hokuyo_scan_frame,
+    data_type: LaserScan,
+    topic: /robot/sensors/rear_scan,
+    observation_persistence: 0.0,
+    marking: true,
+    clearing: true,
+    min_obstacle_height: 0.05,
+    max_obstacle_height: 1.8,
+    expected_update_rate: 10,
+    obstacle_range: 30.0,
+    raytrace_range: 40.0
+  }
+
+inflation_layer:
+  enabled: true
+  inflate_unknown: false
+  inflation_radius: 2.0
+  cost_scaling_factor:  5.0
+  inflation_radius:     0.5
diff --git a/params/costmap/local_params.yaml b/params/costmap/local_params.yaml
new file mode 100644
index 0000000..54ec429
--- /dev/null
+++ b/params/costmap/local_params.yaml
@@ -0,0 +1,15 @@
+#local_costmap:  ###namespace added when loading parameters in move_base.launch
+global_frame: /robot/odom
+update_frequency: 5.0
+publish_frequency: 2.0
+rolling_window: true
+width: 10.0
+height: 10.0
+resolution: 0.1
+origin_x: 0.0
+origin_y: 0.0
+
+#costmap plugins
+plugins:
+  - {name: obstacle_layer,  type: "costmap_2d::ObstacleLayer"}
+  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
diff --git a/params/costmap/map/global_params.yaml b/params/costmap/map/global_params.yaml
new file mode 100644
index 0000000..aef60d4
--- /dev/null
+++ b/params/costmap/map/global_params.yaml
@@ -0,0 +1,21 @@
+#global_costmap: ###namespace added when loading parameters in move_base.launch
+global_frame: /map
+update_frequency: 1.0
+publish_frequency: 0.0
+rolling_window: false
+
+plugins:
+  - {name: static_layer,    type: "costmap_2d::StaticLayer"}
+  - {name: obstacle_layer,  type: "costmap_2d::ObstacleLayer"}
+  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
+    
+static_layer:
+  enabled: true
+  map_topic: /map
+  first_map_only: false
+  subscribe_to_updates: false
+  unknown_cost_value: -1
+  use_maximum: false
+  lethal_cost_threshold: 100
+  track_unknown_space: true
+  trinary_costmap: true
\ No newline at end of file
diff --git a/params/costmap/no_map/global_params.yaml b/params/costmap/no_map/global_params.yaml
new file mode 100644
index 0000000..a72fe5e
--- /dev/null
+++ b/params/costmap/no_map/global_params.yaml
@@ -0,0 +1,15 @@
+#global_costmap: ###namespace added when loading parameters in move_base.launch
+global_frame: /robot/odom
+update_frequency: 1.0
+publish_frequency: 0.0
+rolling_window: true
+transform_tolerance: 1.0
+width: 20.0
+height: 20.0
+resolution: 0.2
+origin_x: 0.0
+origin_y: 0.0
+
+plugins:
+  - {name: obstacle_layer,  type: "costmap_2d::VoxelLayer"}
+  - {name: inflation_layer, type: "costmap_2d::InflationLayer"}
\ No newline at end of file
diff --git a/params/global_planner/global_planner_params.yaml b/params/global_planner/global_planner_params.yaml
new file mode 100644
index 0000000..43e309e
--- /dev/null
+++ b/params/global_planner/global_planner_params.yaml
@@ -0,0 +1,22 @@
+base_global_planner: "global_planner/GlobalPlanner"
+
+GlobalPlanner: #default
+  allow_unknown: false 
+  default_tolerance: 0.0 
+  publish_potential: false 
+  publish_scale: 100
+  old_navfn_behavior: false 
+  planner_costmap_publish_frequency: 0.0
+#planner to use
+  use_dijkstra: true 
+  use_quadratic: true 
+  use_grid_path: false 
+# planner parameters
+  lethal_cost: 253
+  neutral_cost: 50
+  cost_factor: 3.0
+  planner_window_x: 0.0
+  planner_window_y: 0.0
+# orientation fileter
+  orientation_mode: 0
+  orientation_window_size: 1 
diff --git a/params/gmapping_default.yaml b/params/gmapping.yaml
similarity index 100%
rename from params/gmapping_default.yaml
rename to params/gmapping.yaml
diff --git a/params/local_planner/dwa_params.yaml b/params/local_planner/dwa_params.yaml
new file mode 100644
index 0000000..38a3b40
--- /dev/null
+++ b/params/local_planner/dwa_params.yaml
@@ -0,0 +1,54 @@
+base_local_planner: "dwa_local_planner/DWAPlannerROS"
+latch_xy_goal_tolerance: true 
+
+DWAPlannerROS:
+# robot configuration parameters
+  max_trans_vel: 0.5
+  min_trans_vel: 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:  2.0
+  min_rot_vel: -2.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
+  trans_stopped_vel: 0.1
+
+# goal tolerance parameters
+  xy_goal_tolerance: 0.1 
+  yaw_goal_tolerance: 0.1 
+
+# Forward simulation parameters
+  sim_time: 2.5
+  sim_granularity: 0.1
+  angular_sim_granularity: 0.1
+  vx_samples: 21
+  vy_samples: 1 
+  vth_samples: 20
+  controller_frequency: 20.0 # defines the sim_period
+
+# Trajectory scoring parameters
+  path_distance_bias: 32.0
+  goal_distance_bias: 32.0
+  occdist_scale: 0.01
+  twirling_scale: 0.0
+  stop_time_buffer: 0.2
+  forward_point_distance: 0.325
+  scaling_speed: 0.25
+  max_scaling_factor: 0.2
+
+# Oscillation prevention parameters
+  oscillation_reset_dist: 0.05
+  oscillation_reset_angle: 0.2
+  
+# global plan parameters
+  prune_plan: true
+
+  #not in dynamic reconfigure
+  publish_traj_pc: false
+  #global_frame_id: /robot/base_footprint
+  publish_cost_grid_pc: false
diff --git a/params/move_base_params.yaml b/params/move_base_params.yaml
new file mode 100644
index 0000000..d64f555
--- /dev/null
+++ b/params/move_base_params.yaml
@@ -0,0 +1,23 @@
+#base_global_planner: #defined in the global planner parameter file
+#base_local_planner: #define in the local planner parameter file
+
+recovery_behavior_enabled: false
+recovery_behaviors:
+  - {name: conservative_reset, type: clear_costmap_recovery/ClearCostmapRecovery}
+  - {name: rotate_recovery, type: rotate_recovery/RotateRecovery}
+  - {name: aggressive_reset, type: clear_costmap_recovery/ClearCostmapRecovery}
+
+controller_frequency: 10.0
+planner_patience: 5.0
+controller_patience: 5.0
+planner_frequency: 0.0 
+max_planning_retries: -1 
+
+conservative_reset_dist: 3.0
+
+clearing_rotation_allowed: false
+clearing_radius: 0.46 
+shutdown_costmaps: false
+
+oscillation_timeout: 0.0
+oscillation_distance: 0.5
diff --git a/params/cmdvelmux_default.yaml b/params/mux.yaml
similarity index 100%
rename from params/cmdvelmux_default.yaml
rename to params/mux.yaml
-- 
GitLab