]> defiant.homedns.org Git - ros_roboint.git/commitdiff
navigation stack seems to work now
authorerik <erik@ROS.(none)>
Sun, 25 Aug 2013 19:22:37 +0000 (21:22 +0200)
committererik <erik@ROS.(none)>
Sun, 25 Aug 2013 19:22:37 +0000 (21:22 +0200)
config/base_local_planner_params.yaml
config/local_costmap_params.yaml
move_base.launch
scripts/robo_explorer.py

index 7d670be12befaf38416cd6cf277987e8e01a0e5b..aee88f6cecc95d4fd58bce1dafdcc2eb4d4c1297 100644 (file)
@@ -10,4 +10,5 @@ TrajectoryPlannerROS:
 
   holonomic_robot: false
 
-  yaw_goal_tolerance: 0.2
+  yaw_goal_tolerance: 0.1
+  meter_scoring: true
index 523c9f0b8111e2d0bd90c6042e302a7f34ed4ec9..a8a92d550cce388eb6dc516d461597e85d601454 100644 (file)
@@ -7,4 +7,4 @@ local_costmap:
   rolling_window: true
   width: 4.0
   height: 4.0
-  resolution: 0.5
+  resolution: 0.05
index 6c750989ee4332ffad6e245d7a3279ef4179af6e..37874d25746c145a513ed0be8e55f9417a63e202 100644 (file)
@@ -2,7 +2,7 @@
        <master auto="start"/>
 
        <!-- Run the map server -->
-       <node name="map_server" pkg="map_server" type="map_server" args="$(find roboint)/config/map.pgm 0.5"/>
+       <node name="map_server" pkg="map_server" type="map_server" args="$(find roboint)/config/map.pgm 0.05"/>
 
        <!-- Run AMCL -->
        <include file="$(find amcl)/examples/amcl_diff.launch" />
index 22ea4d0efc288d232dc18f4a58ea45c90b19220b..693a8d0110bd53ef571e6adf4cecce67355562b4 100755 (executable)
@@ -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