]> defiant.homedns.org Git - ros_roboint.git/blobdiff - scripts/robo_explorer.py
robo_explorer: only publish scan if enabled
[ros_roboint.git] / scripts / robo_explorer.py
index 22ea4d0efc288d232dc18f4a58ea45c90b19220b..e0da2ac9c6b3fe84ac68b34653077f17b45fd6bc 100755 (executable)
@@ -2,6 +2,8 @@
 import roslib; roslib.load_manifest('roboint')
 import rospy
 import tf
+import tf.broadcaster
+import tf.transformations
 from math import sin, cos, pi
 from geometry_msgs.msg import Twist, TransformStamped, Point32
 from sensor_msgs.msg import LaserScan
@@ -14,22 +16,24 @@ class RoboExplorer:
        def __init__(self):
                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.speed = (0, 0)
                self.x = 0
                self.y = 0
                self.alpha = 0
                self.last_in = None
-               self.tf_broadcaster = tf.TransformBroadcaster()
+               self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                self.last_time = rospy.Time.now()
-               self.input_count = 0
                self.x_last = 0
                self.y_last = 0
                self.alpha_last = 0
 
+               self.enable_ultrasonic_laser = int(rospy.get_param('~ultrasonic_laser', "1"))
+               self.wheel_dist = float(rospy.get_param('~wheel_dist', "0.188"))
+               self.wheel_size = float(rospy.get_param('~wheel_size', "0.0255"))
+
                self.pub_motor = rospy.Publisher("ft/set_motor", Motor)
-               self.pub_scan = rospy.Publisher("scan", LaserScan)
+               if self.enable_ultrasonic_laser:
+                       self.pub_scan = rospy.Publisher("scan", LaserScan)
                self.pub_odom = rospy.Publisher("odom", Odometry)
                
                rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
@@ -39,16 +43,16 @@ class RoboExplorer:
 
        def inputsReceived(self, msg):
                current_time = rospy.Time.now()
-               self.input_count+=1
 
                self.update_odometry(msg, current_time)
-               if self.input_count >= 10:
-                       self.input_count = 0
+               if (current_time - self.last_time).to_nsec() > 100e6: # send every 100ms
                        self.send_odometry(msg, current_time)
-                       self.send_laser_scan(msg, current_time)
+                       if self.enable_ultrasonic_laser:
+                               self.send_laser_scan(msg, current_time)
+                       self.last_time = current_time
 
        def update_odometry(self, msg, current_time):
-               in_now = msg.input[1:3]
+               in_now = msg.input[:2]
                if self.last_in is not None:
                        in_diff = [abs(a - b) for a, b in zip(in_now, self.last_in)] # get changed inputs
                        # fix in_diff from actual motor direction
@@ -85,7 +89,6 @@ class RoboExplorer:
                vx = (self.x - self.x_last) / dt
                vy = (self.y - self.y_last) / dt
                valpha = (self.alpha - self.alpha_last) / dt
-               self.last_time = current_time
                self.x_last = self.x
                self.y_last = self.y
                self.alpha_last = self.alpha
@@ -124,7 +127,7 @@ class RoboExplorer:
                self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link")
 
                # actually ultra sonic range finder
-               num_points = 30
+               num_points = 60 # The base planner needs at least 30 points to work in the default config
                opening_angle = 30*pi/180 # each side
                scan = LaserScan()
                scan.header.stamp = current_time
@@ -132,7 +135,7 @@ class RoboExplorer:
                scan.angle_min = -opening_angle
                scan.angle_max = opening_angle
                scan.angle_increment = (2*opening_angle)/num_points
-               scan.time_increment = 0.1/num_points
+               scan.time_increment = 0.0
                scan.range_min = 0.0
                scan.range_max = 4.0
                for i in range(num_points):
@@ -170,6 +173,8 @@ 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))
+
                outmsg = Motor()
                outmsg.num = 1
                outmsg.speed = round(speed_l)