]> defiant.homedns.org Git - ros_wild_thumper.git/commitdiff
move_base: support for srf & ir
authorErik Andresen <erik@vontaene.de>
Thu, 7 May 2015 11:37:16 +0000 (13:37 +0200)
committerErik Andresen <erik@vontaene.de>
Thu, 7 May 2015 11:37:16 +0000 (13:37 +0200)
scripts/move_base.py

index 6886ec0cbfd69a303bcea8ff482c6aa61397ba2d..bac2742386fd45c2c6b3e2c69bef366507835fac 100755 (executable)
@@ -20,6 +20,10 @@ class MoveBase:
        def run(self):
                rate = rospy.Rate(10.0)
                while not rospy.is_shutdown():
+                       #self.get_dist_forward()
+                       #self.get_dist_backward()
+                       #self.get_dist_left()
+                       #self.get_dist_right()
                        rate.sleep()
 
        def set_speed(self, left, right):
@@ -46,6 +50,48 @@ class MoveBase:
                left = trans*2-right
                self.set_speed(left, right)
 
+       # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
+       def get_dist_ir(self, num):
+               dev = i2c(0x52)
+               s = struct.pack("B", num)
+               dev.write(s)
+               dev.close()
+
+               sleep(2e-6)
+
+               dev = i2c(0x52)
+               s = dev.read(2)
+               dev.close()
+
+               val = struct.unpack(">H", s)[0]
+               return 15221/(val - -276.42)/100;
+       
+       def get_dist_srf(self, num):
+               dev = i2c(0x52)
+               s = struct.pack("B", num)
+               dev.write(s)
+               dev.close()
+
+               sleep(50e-3)
+
+               dev = i2c(0x52)
+               s = dev.read(2)
+               dev.close()
+
+               return struct.unpack(">H", s)[0]/1000.0
+
+       def get_dist_left(self):
+               dist = self.get_dist_ir(0x1)
+
+       def get_dist_right(self):
+                dist = self.get_dist_ir(0x3)
+
+       def get_dist_forward(self):
+               dist = self.get_dist_srf(0x5)
+
+       def get_dist_backward(self):
+               dist = self.get_dist_srf(0x7)
+
 
 if __name__ == "__main__":
        MoveBase()