]> defiant.homedns.org Git - ros_roboint.git/blobdiff - scripts/robo_explorer.py
use new inflation_layer in layered costmap2d
[ros_roboint.git] / scripts / robo_explorer.py
index de755c10c38abbb52fb0261ccd2ed5689282e415..bf3522927532cc94d8223e0fd9628448ccb5344c 100755 (executable)
@@ -3,8 +3,8 @@ import roslib; roslib.load_manifest('roboint')
 import rospy
 import tf
 from math import *
-from geometry_msgs.msg import Twist, TransformStamped, Point32
-from sensor_msgs.msg import LaserScan
+from geometry_msgs.msg import Twist, TransformStamped, Point32, PoseWithCovarianceStamped
+from sensor_msgs.msg import Range
 from nav_msgs.msg import Odometry
 from roboint.msg import Motor
 from roboint.msg import Inputs
@@ -24,8 +24,6 @@ class RoboExplorer:
                self.y_last = 0
                self.alpha_last = 0
 
-               # 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.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 
@@ -35,15 +33,22 @@ class RoboExplorer:
                # 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:
-                       self.pub_scan = rospy.Publisher("scan", LaserScan)
-               self.pub_odom = rospy.Publisher("odom", Odometry)
+               self.pub_motor = rospy.Publisher("ft/set_motor", Motor, queue_size=16)
+               self.pub_sonar = rospy.Publisher("sonar", Range, queue_size=16)
+               self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
                
                rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
                rospy.Subscriber("ft/get_inputs", Inputs, self.inputsReceived)
+               rospy.Subscriber("initialpose", PoseWithCovarianceStamped, self.posReceived)
 
                rospy.spin()
+       
+       def posReceived(self, msg):
+               self.x = msg.pose.pose.position.x
+               self.y = msg.pose.pose.position.y
+               orientation = msg.pose.pose.orientation
+               angles = tf.transformations.euler_from_quaternion([orientation.x, orientation.y, orientation.z, orientation.w])
+               self.alpha = angles[2]
 
        def inputsReceived(self, msg):
                current_time = rospy.Time.now()
@@ -51,8 +56,7 @@ 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)
-                       if self.enable_ultrasonic_laser:
-                               self.send_laser_scan(msg, current_time)
+                       self.send_range(msg, current_time)
                        self.last_time = current_time
 
        def update_odometry(self, msg, current_time):
@@ -69,10 +73,10 @@ class RoboExplorer:
                        elif msg.output[2] == 0 and msg.output[3] == 0: # right stop
                                in_diff[1] = 0
 
-                       dist_dir = (in_diff[1] - in_diff[0])*self.wheel_size*pi/8 # steps_changed in different direction => m
+                       dist_dir = (in_diff[1] - in_diff[0]) * self.wheel_size*pi/8 # steps_changed in different direction => m
                        delta_alpha = dist_dir/self.wheel_dist
 
-                       dist = (in_diff[0] + in_diff[1])/2.0*self.wheel_size*pi/8 # steps_changed same direction => m
+                       dist = (in_diff[0] + in_diff[1])/2.0 * self.wheel_size*pi/8 # steps_changed same direction => m
 
                        delta_x = cos(self.alpha + delta_alpha/2)*dist
                        delta_y = sin(self.alpha + delta_alpha/2)*dist
@@ -128,28 +132,17 @@ class RoboExplorer:
                # publish the message
                self.pub_odom.publish(odom)
                
-       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")
-
-               # 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()
+       def send_range(self, msg, current_time):
+               # ultra sonic range finder
+               scan = Range()
                scan.header.stamp = current_time
-               scan.header.frame_id = "/scan"
-               scan.angle_min = -opening_angle
-               scan.angle_max = opening_angle
-               scan.angle_increment = (2*opening_angle)/num_points
-               scan.time_increment = 0.0
-               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)
-               self.pub_scan.publish(scan)
+               scan.header.frame_id = "forward_sensor"
+               scan.radiation_type = 0
+               scan.field_of_view = 60*pi/180
+               scan.min_range = 0.0
+               scan.max_range = 4.0
+               scan.range = msg.d1/100.0
+               self.pub_sonar.publish(scan)
 
        # test with rostopic pub -1 cmd_vel geometry_msgs/Twist '[0, 0, 0]' '[0, 0, 0]'
        def cmdVelReceived(self, msg):