]> 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 cfc23fa70aa2868697be8f1b2847a33506f2d093..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,21 +16,24 @@ class RoboExplorer:
        def __init__(self):
                rospy.init_node('robo_explorer')
 
-               self.wheel_dist = 0.188 # 18.8cm
-               self.wheel_size = 0.051*0.5 # 5.1cm; 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.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)
@@ -42,11 +47,12 @@ class RoboExplorer:
                self.update_odometry(msg, current_time)
                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
@@ -129,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.001/num_points
+               scan.time_increment = 0.0
                scan.range_min = 0.0
                scan.range_max = 4.0
                for i in range(num_points):