]> defiant.homedns.org Git - ros_roboint.git/blobdiff - scripts/robo_explorer.py
added readme
[ros_roboint.git] / scripts / robo_explorer.py
index 36ec82870a4844c2cbd62a358363f1c614ad7118..cfc23fa70aa2868697be8f1b2847a33506f2d093 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
@@ -23,7 +23,6 @@ class RoboExplorer:
                self.last_in = None
                self.tf_broadcaster = tf.TransformBroadcaster()
                self.last_time = rospy.Time.now()
-               self.input_count = 0
                self.x_last = 0
                self.y_last = 0
                self.alpha_last = 0
@@ -39,14 +38,12 @@ 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
-                       self.tf_broadcaster.sendTransform((0.0, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "odom", "map");
+               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)
+                       self.last_time = current_time
 
        def update_odometry(self, msg, current_time):
                in_now = msg.input[1:3]
@@ -86,7 +83,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
@@ -95,7 +91,7 @@ class RoboExplorer:
                odom_quat = tf.transformations.quaternion_from_euler(0, 0, self.alpha)
 
                # first, we'll publish the transform over tf
-               self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom");
+               self.tf_broadcaster.sendTransform((self.x, self.y, 0.0), odom_quat, current_time, "base_link", "odom")
 
                # next, we'll publish the odometry message over ROS
                odom = Odometry()
@@ -112,7 +108,7 @@ class RoboExplorer:
                odom.pose.pose.orientation.w = odom_quat[3]
 
                # set the velocity
-               odom.child_frame_id = "base_link";
+               odom.child_frame_id = "base_link"
                odom.twist.twist.linear.x = vx
                odom.twist.twist.linear.y = vy
                odom.twist.twist.angular.z = valpha
@@ -122,23 +118,25 @@ class RoboExplorer:
                
        def send_laser_scan(self, msg, current_time):
                # first, we'll publish the transform over tf
-               self.tf_broadcaster.sendTransform((0.06, 0.0, 0.0), (0.0, 0.0, 0.0, 1.0), current_time, "scan", "base_link");
+               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 = 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
                scan.header.frame_id = "/scan"
-               scan.angle_min = -pi/4;
-               scan.angle_max = pi/4;
-               scan.angle_increment = pi/4;
-               scan.time_increment = 0.1;
-               scan.range_min = 0.0;
-               scan.range_max = 4.0;
-               for i in range(3):
+               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.range_min = 0.0
+               scan.range_max = 4.0
+               for i in range(num_points):
                        scan.ranges.append(msg.d1/100.0)
-               scan.intensities.append(0.5)
-               scan.intensities.append(1.0)
-               scan.intensities.append(0.5)
+               #scan.intensities.append(0.5)
+               #scan.intensities.append(1.0)
+               #scan.intensities.append(0.5)
                self.pub_scan.publish(scan)
 
        # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
@@ -169,6 +167,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)