]> defiant.homedns.org Git - ros_roboint.git/commitdiff
robo_explorer: more settings
authorErik Andresen <erik@vontaene.de>
Thu, 5 Sep 2013 15:25:30 +0000 (17:25 +0200)
committerErik Andresen <erik@vontaene.de>
Thu, 5 Sep 2013 15:25:30 +0000 (17:25 +0200)
README
explorer_configuration.launch
scripts/robo_explorer.py

diff --git a/README b/README
index d772dd31cf2eea01c3ccf20ab871df005780bf4f..8e6dd950a3f5e2014fc5551117617365d38c0d24 100644 (file)
--- a/README
+++ b/README
@@ -8,7 +8,7 @@ Its is split in the Nodes:
 -robo_explorer.py: Provides the Robo Explorer functions:
  Laserscan is faked by the Sonar Sensor.
 
-You need to use Robo Explorer with Wheels instead of Tracks because the Tracks are too inaccurate for Odometry.
+You need to use the Robo Explorer with Wheels instead of Tracks because the Tracks are too inaccurate for Odometry.
 I used the Wheel Setup from Mobile Robots 2.
 
 
@@ -42,4 +42,7 @@ Commands:
 -Start RViz:
 # rosrun rviz rviz
 -Manually setting of Translation/Rotation speed:
-# rostopic pub -1 cmd_vel geometry_msgs/Twist '[0.0, 0, 0]' '[0, 0, 0.0]'
+ Forward:
+# 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]'
index 71d23bdfb1d20302c2ef239798927a77f1feea46..5aadc57fdd03768dd0a1e2f9c387c3483305925a 100644 (file)
@@ -4,7 +4,7 @@
 
        <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="1" />
+               <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 -->
index e0da2ac9c6b3fe84ac68b34653077f17b45fd6bc..f39c9c46732ad3bcd71bff05d25c5246b2154094 100755 (executable)
@@ -27,9 +27,16 @@ class RoboExplorer:
                self.y_last = 0
                self.alpha_last = 0
 
-               self.enable_ultrasonic_laser = int(rospy.get_param('~ultrasonic_laser', "1"))
+               # 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"))
+               # 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)
+               self.speed_constant = float(rospy.get_param('~speed_constant', "-1.7"))
 
                self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
                if self.enable_ultrasonic_laser:
@@ -156,14 +163,14 @@ class RoboExplorer:
                # handle translation
                speed_l = 0
                wish_speed_left = trans - speed_offset
-               if abs(wish_speed_left) > 1.7/64.3:
-                       speed_l = 64.3*abs(wish_speed_left) - 1.7
+               if abs(wish_speed_left) > 0:
+                       speed_l = self.speed_gradiant*abs(wish_speed_left) + self.speed_constant
                        if wish_speed_left < 0:
                                speed_l*=-1
                speed_r = 0
                wish_speed_right = trans + speed_offset
-               if abs(wish_speed_right) > 1.7/64.3:
-                       speed_r = 64.3*abs(wish_speed_right) - 1.7
+               if abs(wish_speed_right) > 0:
+                       speed_r = self.speed_gradiant*abs(wish_speed_right) + self.speed_constant
                        if wish_speed_right < 0:
                                speed_r*=-1
 
@@ -173,7 +180,7 @@ class RoboExplorer:
                if speed_r < -7: speed_r = -7
                elif speed_r > 7: speed_r = 7
 
-               #print "Speed wanted: %.2f %.2f, set: %d %d" % (trans, rot*180/pi, round(speed_l), round(speed_r))
+               #print "Speed wanted: %.2f m/s %.2f rad/s, set: %d %d" % (trans, rot, round(speed_l), round(speed_r))
 
                outmsg = Motor()
                outmsg.num = 1