diff --git a/rois_2dnav_gazebo/config/amcl_params.yaml b/rois_2dnav_gazebo/config/amcl_params.yaml index dd2fe271fb234f4c07823a31da77b20049736a19..1d18d803b4add01834aaafd65f44f4317b3a5eca 100644 --- a/rois_2dnav_gazebo/config/amcl_params.yaml +++ b/rois_2dnav_gazebo/config/amcl_params.yaml @@ -4,12 +4,12 @@ max_particles: 5000 kld_err: 0.01 kld_z: 0.99 -update_min_d: 0.01 -update_min_a: 0.01 +update_min_d: 0.2 +update_min_a: 0.2 resample_interval: 2 -transform_tolerance: 0.1 +transform_tolerance: 0.5 recovery_alpha_slow: 0.001 recovery_alpha_fast: 0.1 diff --git a/rois_2dnav_gazebo/config/costmap/robot1/global_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/robot1/global_costmap_params.yaml index f892f5584d0aacd6f1b2065a0ece3c10ddeeea66..d89bc59c52cd9e5c1fa74bbca669930b0456a77d 100644 --- a/rois_2dnav_gazebo/config/costmap/robot1/global_costmap_params.yaml +++ b/rois_2dnav_gazebo/config/costmap/robot1/global_costmap_params.yaml @@ -1,8 +1,8 @@ global_costmap: global_frame: map robot_base_frame: robot1/base_footprint - update_frequency: 3.0 - publish_frequency: 3.0 + update_frequency: 0.5 + publish_frequency: 0.5 static_map: true rolling_window: false transform_tolerance: 1.0 diff --git a/rois_2dnav_gazebo/config/costmap/robot1/local_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/robot1/local_costmap_params.yaml index d21d3bff3d3e0fdcb9a8425868f4c85ba701c73f..498e2ce3435bf59e49929022f4788fb03bf347f2 100644 --- a/rois_2dnav_gazebo/config/costmap/robot1/local_costmap_params.yaml +++ b/rois_2dnav_gazebo/config/costmap/robot1/local_costmap_params.yaml @@ -1,8 +1,8 @@ local_costmap: global_frame: robot1/odom robot_base_frame: robot1/base_footprint - update_frequency: 8.0 - publish_frequency: 7.0 + update_frequency: 1.0 + publish_frequency: 1.0 width: 10.0 height: 10.0 resolution: 0.02 diff --git a/rois_2dnav_gazebo/config/costmap/robot2/global_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/robot2/global_costmap_params.yaml index a318075de7c61979ee797ec80df15fb869fbc385..782298707a9971d121b7317204c98b53f64d09e2 100644 --- a/rois_2dnav_gazebo/config/costmap/robot2/global_costmap_params.yaml +++ b/rois_2dnav_gazebo/config/costmap/robot2/global_costmap_params.yaml @@ -1,8 +1,8 @@ global_costmap: global_frame: map robot_base_frame: robot2/base_footprint - update_frequency: 3.0 - publish_frequency: 3.0 + update_frequency: 0.5 + publish_frequency: 0.5 static_map: true rolling_window: false transform_tolerance: 1.0 diff --git a/rois_2dnav_gazebo/config/costmap/robot2/local_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/robot2/local_costmap_params.yaml index 8065ad90629f4baca230e76bb829914e3655ffba..c5a36220c781f15f4018f5c1fe2b3c63ee342f7b 100644 --- a/rois_2dnav_gazebo/config/costmap/robot2/local_costmap_params.yaml +++ b/rois_2dnav_gazebo/config/costmap/robot2/local_costmap_params.yaml @@ -1,8 +1,8 @@ local_costmap: global_frame: robot2/odom robot_base_frame: robot2/base_footprint - update_frequency: 8.0 - publish_frequency: 7.0 + update_frequency: 1.0 + publish_frequency: 1.0 width: 10.0 height: 10.0 resolution: 0.02 diff --git a/rois_2dnav_gazebo/config/costmap/robot3/global_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/robot3/global_costmap_params.yaml index 9f0bd7e552b7be0621ba53da1f9a1a22287df6c8..72d2c6e1f9339abd7127a3c87ed722f193dbef6d 100644 --- a/rois_2dnav_gazebo/config/costmap/robot3/global_costmap_params.yaml +++ b/rois_2dnav_gazebo/config/costmap/robot3/global_costmap_params.yaml @@ -1,8 +1,8 @@ global_costmap: global_frame: map robot_base_frame: robot3/base_footprint - update_frequency: 3.0 - publish_frequency: 3.0 + update_frequency: 0.5 + publish_frequency: 0.5 static_map: true rolling_window: false transform_tolerance: 1.0 diff --git a/rois_2dnav_gazebo/config/costmap/robot3/local_costmap_params.yaml b/rois_2dnav_gazebo/config/costmap/robot3/local_costmap_params.yaml index 2f5a5af986a1183dea8354a08a9722af84f66368..2e83eacb400e7c3e8739c14124fc143d9e1c9bfc 100644 --- a/rois_2dnav_gazebo/config/costmap/robot3/local_costmap_params.yaml +++ b/rois_2dnav_gazebo/config/costmap/robot3/local_costmap_params.yaml @@ -1,8 +1,8 @@ local_costmap: global_frame: robot3/odom robot_base_frame: robot3/base_footprint - update_frequency: 8.0 - publish_frequency: 7.0 + update_frequency: 1.0 + publish_frequency: 1.0 width: 10.0 height: 10.0 resolution: 0.02 diff --git a/rois_2dnav_gazebo/config/move_base_params.yaml b/rois_2dnav_gazebo/config/move_base_params.yaml index 86ed2ca14d818d15974e56d5d89ecba8869dacc4..0d8ca0b0f0b428e2e205090fe3dca1f717d0be0e 100644 --- a/rois_2dnav_gazebo/config/move_base_params.yaml +++ b/rois_2dnav_gazebo/config/move_base_params.yaml @@ -1,4 +1,4 @@ -controller_frequency: 5.0 +controller_frequency: 2.0 controller_patience: 10.0 planner_patience: 5.0 diff --git a/rois_2dnav_gazebo/config/planner/base_local_planner_params.yaml b/rois_2dnav_gazebo/config/planner/base_local_planner_params.yaml index 7459a1ab8b94d665ace62afbb314f9c3a3a69532..5f4e95e2f86ba48eafae6d19b659d304817ca631 100644 --- a/rois_2dnav_gazebo/config/planner/base_local_planner_params.yaml +++ b/rois_2dnav_gazebo/config/planner/base_local_planner_params.yaml @@ -4,7 +4,7 @@ TrajectoryPlannerROS: max_vel_theta: 2.0 min_vel_theta: -2.0 - min_in_place_rotational_vel: 1.0 + min_in_place_vel_theta: 1.0 acc_lim_x: 1.0 acc_lim_y: 0.0 @@ -16,7 +16,7 @@ TrajectoryPlannerROS: xy_goal_tolerance: 2.0 sim_time: 2.0 - controller_frequency: 5.0 + controller_frequency: 2.0 # Length of view when rotate heading_lookahead: 15.0 # Use method of Dynamic Window Approach @@ -28,4 +28,4 @@ TrajectoryPlannerROS: publish_cost_grid_pc: true global_frame_id: /map - meter_scoring: false + meter_scoring: true