From: erik Date: Sun, 25 Aug 2013 19:22:37 +0000 (+0200) Subject: navigation stack seems to work now X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_roboint.git;a=commitdiff_plain;h=37a6abd81e2df14d5cac07d99fa854f308355918 navigation stack seems to work now --- diff --git a/config/base_local_planner_params.yaml b/config/base_local_planner_params.yaml index 7d670be..aee88f6 100644 --- a/config/base_local_planner_params.yaml +++ b/config/base_local_planner_params.yaml @@ -10,4 +10,5 @@ TrajectoryPlannerROS: holonomic_robot: false - yaw_goal_tolerance: 0.2 + yaw_goal_tolerance: 0.1 + meter_scoring: true diff --git a/config/local_costmap_params.yaml b/config/local_costmap_params.yaml index 523c9f0..a8a92d5 100644 --- a/config/local_costmap_params.yaml +++ b/config/local_costmap_params.yaml @@ -7,4 +7,4 @@ local_costmap: rolling_window: true width: 4.0 height: 4.0 - resolution: 0.5 + resolution: 0.05 diff --git a/move_base.launch b/move_base.launch index 6c75098..37874d2 100644 --- a/move_base.launch +++ b/move_base.launch @@ -2,7 +2,7 @@ - + diff --git a/scripts/robo_explorer.py b/scripts/robo_explorer.py index 22ea4d0..693a8d0 100755 --- a/scripts/robo_explorer.py +++ b/scripts/robo_explorer.py @@ -15,7 +15,7 @@ class RoboExplorer: rospy.init_node('robo_explorer') self.wheel_dist = 0.188 # 18.8cm - self.wheel_size = 0.052*0.5 # 5.2cm; gear ration=0.5 + self.wheel_size = 0.051*0.5 # 5.1cm; gear ration=0.5 self.speed = (0, 0) self.x = 0 self.y = 0