From: Erik Andresen Date: Sat, 7 Jan 2017 19:43:02 +0000 (+0100) Subject: tune slam gmapping X-Git-Url: https://defiant.homedns.org/gitweb/?a=commitdiff_plain;h=670ead7985c1c4df661d9e95e20a0b805c0347f8;p=ros_wild_thumper.git tune slam gmapping --- diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index b48a72f..0ce322b 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -8,14 +8,21 @@ TrajectoryPlannerROS: acc_lim_x: 10.07 acc_lim_y: 0.0 - acc_lim_theta: 12.00 + acc_lim_theta: 6.00 holonomic_robot: false + # gdist_scale and pdist_scale parameters should assume meters meter_scoring: true xy_goal_tolerance: 0.20 yaw_goal_tolerance: 0.3 + # The weighting for how much the controller should attempt to avoid obstacles, default: 0.01 + occdist_scale: 0.02 + + # Whether to score based on the robot's heading to the path or its distance from the path, default: false + heading_scoring: true + DWAPlannerROS: acc_lim_x: 10.07 acc_lim_y: 0.0 diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml index 674c1cc..5662912 100644 --- a/config/costmap_common_params.yaml +++ b/config/costmap_common_params.yaml @@ -7,7 +7,7 @@ obstacle_layer: laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true} inflation_layer: - inflation_radius: 0.25 + inflation_radius: 0.20 range_layer: topics: ["/range_forward", "/range_backward", "/range_left", "/range_right"] diff --git a/config/costmap_exploration.yaml b/config/costmap_exploration.yaml index 6368563..84c88ef 100644 --- a/config/costmap_exploration.yaml +++ b/config/costmap_exploration.yaml @@ -22,13 +22,8 @@ static_layer: # map_topic: move_base/global_costmap/costmap subscribe_to_updates: true -range_layer: - topics: ["/range_forward", "/range_backward"] - no_readings_timeout: 1.0 - clear_on_max_reading: true - explore_boundary: resize_to_boundary: false frontier_travel_point: middle # set to false for gmapping, true if re-exploring a known area - explore_clear_space: true + explore_clear_space: false diff --git a/launch/exploration.launch b/launch/exploration.launch index 4df3aee..6d8e4de 100644 --- a/launch/exploration.launch +++ b/launch/exploration.launch @@ -3,7 +3,7 @@ - + diff --git a/launch/gmapping.launch b/launch/gmapping.launch new file mode 100644 index 0000000..03ce798 --- /dev/null +++ b/launch/gmapping.launch @@ -0,0 +1,36 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/launch/model.launch b/launch/model.launch deleted file mode 100644 index 8e4079b..0000000 --- a/launch/model.launch +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/launch/move_base.launch b/launch/move_base.launch index 3c1880d..88705b9 100644 --- a/launch/move_base.launch +++ b/launch/move_base.launch @@ -14,23 +14,7 @@ - - - - - - - - - - - - - - - - - +