2 # -*- coding: iso-8859-15 -*-
8 from geometry_msgs.msg import Twist
14 rospy.init_node('wild_thumper_move_base')
15 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
17 rospy.loginfo("Init done")
18 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
22 rate = rospy.Rate(20.0)
23 while not rospy.is_shutdown():
25 #self.get_dist_forward()
26 #self.get_dist_backward()
28 #self.get_dist_right()
32 s = i2c_read_reg(0x50, 0x10, 8)
33 hall1, hall2, hall3, hall4 = struct.unpack(">hhhh", s)
34 print hall1, hall2, hall3, hall4
36 def set_speed(self, left, right):
38 elif left < 0: left-=80
39 if right > 0: right+=80
40 elif right < 0: right-=80
42 if left > 255: left=255
43 elif left < -255: left=-255
44 if right > 255: right=255
45 elif right < -255: right=-255
47 i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", right, right, left, left))
49 def cmdVelReceived(self, msg):
51 rot = msg.angular.z # rad/s
53 right = rot*pi*WHEEL_DIST + trans
55 self.set_speed(left, right)
57 # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
58 def get_dist_ir(self, num):
60 s = struct.pack("B", num)
70 val = struct.unpack(">H", s)[0]
71 return 15221/(val - -276.42)/100;
73 def get_dist_srf(self, num):
75 s = struct.pack("B", num)
85 return struct.unpack(">H", s)[0]/1000.0
87 def get_dist_left(self):
88 dist = self.get_dist_ir(0x1)
90 def get_dist_right(self):
91 dist = self.get_dist_ir(0x3)
93 def get_dist_forward(self):
94 dist = self.get_dist_srf(0x5)
96 def get_dist_backward(self):
97 dist = self.get_dist_srf(0x7)
100 if __name__ == "__main__":