]> defiant.homedns.org Git - ros_roboint.git/commitdiff
updated values
authorErik Andresen <erik@vontaene.de>
Thu, 5 Sep 2013 16:32:43 +0000 (18:32 +0200)
committerErik Andresen <erik@vontaene.de>
Thu, 5 Sep 2013 16:32:43 +0000 (18:32 +0200)
README
explorer_configuration.launch
scripts/robo_explorer.py

diff --git a/README b/README
index 8e6dd950a3f5e2014fc5551117617365d38c0d24..c5ea4353f37f33a86e4c6727f2f9889f9da6e4f2 100644 (file)
--- a/README
+++ b/README
@@ -46,3 +46,5 @@ Commands:
 # rostopic pub -1 cmd_vel geometry_msgs/Twist '[0.1, 0, 0]' '[0, 0, 0.0]'
  Turn:
 # rostopic pub -1 cmd_vel geometry_msgs/Twist '[0.1, 0, 0]' '[0, 0, 0.4]'
+-Keyboard Control:
+# rosrun pr2_teleop teleop_pr2_keyboard
index 5aadc57fdd03768dd0a1e2f9c387c3483305925a..edfdc1cdd26451d4c52780b2ebb7f7a653a7aa77 100644 (file)
@@ -5,9 +5,9 @@
        <node pkg="roboint" type="robo_explorer.py" name="robo_explorer" output="screen">
                <!-- fake laser scan with ultra sonic range finder -->
                <param name="ultrasonic_laser" value="True" />
-               <!-- Distance between both wheels in meter (18.8cm) -->
-               <param name="wheel_dist" value="0.188" />
-               <!-- Size of wheel Diameter in meter (5.1cm) * gear ratio (0.5) = 2.55cm -->
-               <param name="wheel_size" value="0.0255" />
+               <!-- Distance between both wheels in meter (18.55cm) -->
+               <param name="wheel_dist" value="0.1855" />
+               <!-- Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm -->
+               <param name="wheel_size" value="0.02575" />
        </node>
 </launch>
index f39c9c46732ad3bcd71bff05d25c5246b2154094..24584e78a3443e82a900b530e0925f1d717a8095 100755 (executable)
@@ -29,10 +29,10 @@ class RoboExplorer:
 
                # fake laser scan with ultra sonic range finder
                self.enable_ultrasonic_laser = bool(rospy.get_param('~ultrasonic_laser', "True"))
-               # Distance between both wheels in meter (18.8cm)
-               self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.188"))
-               # Size of wheel Diameter in meter (5.1cm) * gear ratio (0.5) = 2.55cm 
-               self.wheel_size = float(rospy.get_param('~wheel_size', "0.0255"))
+               # Distance between both wheels in meter (18.55cm)
+               self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.1855"))
+               # Size of wheel Diameter in meter (5.15cm) * gear ratio (0.5) = 2.575cm 
+               self.wheel_size = float(rospy.get_param('~wheel_size', "0.02575"))
                # Speed to PWM equation gradiant (The m in pwm = speed*m+b)
                self.speed_gradiant = float(rospy.get_param('~speed_gradiant', "64.3"))
                # Speed to PWM equation constant (The b in pwm = speed*m+b)