From: Erik Andresen Date: Sat, 1 Oct 2016 14:56:55 +0000 (+0200) Subject: exploration tuning X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=commitdiff_plain;h=80b61518513631afbd8acdcab2b23a53266080ca exploration tuning --- diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index bbd95c1..b48a72f 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -1,10 +1,10 @@ TrajectoryPlannerROS: min_vel_x: 0.2 - max_vel_x: 0.3 - min_vel_theta: -0.4 - max_vel_theta: 0.4 + max_vel_x: 0.5 + min_vel_theta: -1.0 + max_vel_theta: 1.0 min_in_place_vel_theta: 0.4 - max_rotational_vel: 0.5 # used by rotate recovery + max_rotational_vel: 1.0 # used by rotate recovery acc_lim_x: 10.07 acc_lim_y: 0.0 @@ -28,8 +28,8 @@ DWAPlannerROS: max_trans_vel: 0.5 min_trans_vel: 0.2 - max_rot_vel: 0.5 + max_rot_vel: 1.0 min_rot_vel: 0.4 - xy_goal_tolerance: 0.20 - yaw_goal_tolerance: 0.3 + xy_goal_tolerance: 0.1 + yaw_goal_tolerance: 0.2 diff --git a/config/costmap_common_params.yaml b/config/costmap_common_params.yaml index 6e4b370..02ff12d 100644 --- a/config/costmap_common_params.yaml +++ b/config/costmap_common_params.yaml @@ -1,8 +1,10 @@ footprint: [[0.14, 0.16], [-0.14, 0.16], [-0.14, -0.16], [0.14, -0.16]] -inflation_radius: 0.5 obstacle_layer: observation_sources: laser_scan_sensor obstacle_range: 2.5 raytrace_range: 3.0 laser_scan_sensor: {sensor_frame: camera_depth_frame, data_type: LaserScan, topic: scan, marking: true, clearing: true} + +inflation_layer: + inflation_radius: 0.5 diff --git a/config/costmap_exploration.yaml b/config/costmap_exploration.yaml index 26f3800..0f5bc43 100644 --- a/config/costmap_exploration.yaml +++ b/config/costmap_exploration.yaml @@ -1,20 +1,21 @@ #must match incoming static map global_frame: map -robot_base_frame: base_link -resolution: 0.05 +robot_base_frame: base_footprint +update_frequency: 5.0 +resolution: 0.01 -track_unknown_space: true rolling_window: false +track_unknown_space: true plugins: -- {name: static, type: "costmap_2d::StaticLayer"} +- {name: static_layer, type: 'costmap_2d::StaticLayer'} - {name: explore_boundary, type: "frontier_exploration::BoundedExploreLayer"} #Can disable sensor layer if gmapping is fast enough to update scans -- {name: sensor, type: "costmap_2d::ObstacleLayer"} -- {name: inflation, type: "costmap_2d::InflationLayer"} +- {name: obstacle_layer, type: 'costmap_2d::ObstacleLayer'} +- {name: inflation_layer, type: 'costmap_2d::InflationLayer'} explore_boundary: - resize_to_boundary: false + resize_to_boundary: true frontier_travel_point: middle #set to false for gmapping, true if re-exploring a known area - explore_clear_space: false + explore_clear_space: true diff --git a/data/motor_ctrl_pid_values.ods b/data/motor_ctrl_pid_values.ods index 543fa45..0a1186a 100644 Binary files a/data/motor_ctrl_pid_values.ods and b/data/motor_ctrl_pid_values.ods differ diff --git a/launch/exploration.launch b/launch/exploration.launch index a608265..0c81ea0 100644 --- a/launch/exploration.launch +++ b/launch/exploration.launch @@ -3,7 +3,7 @@ - + diff --git a/launch/move_base.launch b/launch/move_base.launch index a046e6e..2ee4b5a 100644 --- a/launch/move_base.launch +++ b/launch/move_base.launch @@ -3,7 +3,7 @@ - + @@ -29,6 +29,7 @@ + diff --git a/urdf/wild_thumper.urdf.xacro b/urdf/wild_thumper.urdf.xacro index 417123f..1bd641e 100644 --- a/urdf/wild_thumper.urdf.xacro +++ b/urdf/wild_thumper.urdf.xacro @@ -6,7 +6,7 @@ - +