]> defiant.homedns.org Git - ros_wild_thumper.git/blob - scripts/move_base.py
09f823b576dd790073b949f52c784ed85ad5dc3f
[ros_wild_thumper.git] / scripts / move_base.py
1 #!/usr/bin/env python
2 # -*- coding: iso-8859-15 -*-
3
4 import rospy
5 import tf
6 import struct
7 from i2c import *
8 from math import *
9 from geometry_msgs.msg import Twist
10 from nav_msgs.msg import Odometry
11 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
12 from sensor_msgs.msg import Imu
13
14 WHEEL_DIST = 0.248
15
16 class MoveBase:
17         def __init__(self):
18                 rospy.init_node('wild_thumper_move_base')
19                 rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
20                 rospy.Subscriber("imu", Imu, self.imuReceived)
21                 enable_odom_tf = rospy.get_param("~enable_odom_tf", True)
22                 if enable_odom_tf:
23                         self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
24                 else:
25                         self.tf_broadcaster = None
26                 self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
27                 self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
28                 self.set_speed(0, 0)
29                 rospy.loginfo("Init done")
30                 i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction
31                 self.handicap_last = (-1, -1)
32                 self.run()
33         
34         def run(self):
35                 rate = rospy.Rate(20.0)
36                 reset_val = self.get_reset()
37                 rospy.loginfo("Reset Status: 0x%x" % reset_val)
38                 while not rospy.is_shutdown():
39                         #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
40                         self.get_tle_err()
41                         self.get_odom()
42                         self.get_voltage()
43                         #self.get_dist_forward()
44                         #self.get_dist_backward()
45                         #self.get_dist_left()
46                         #self.get_dist_right()
47                         rate.sleep()
48
49         def set_motor_handicap(self, front, aft): # percent
50                 if self.handicap_last != (front, aft):
51                         i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
52                         self.handicap_last = (front, aft)
53
54         def imuReceived(self, msg):
55                 (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
56                 if pitch > 30*pi/180:
57                         val = (100.0/65)*abs(pitch)*180/pi
58                         self.set_motor_handicap(0, int(val))
59                 elif pitch < -30*pi/180:
60                         val = (100.0/65)*abs(pitch)*180/pi
61                         self.set_motor_handicap(int(val), 0)
62                 else:
63                         self.set_motor_handicap(0, 0)
64
65         def get_reset(self):
66                 reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
67
68                 msg = DiagnosticArray()
69                 msg.header.stamp = rospy.Time.now()
70                 stat = DiagnosticStatus()
71                 stat.name = "Reset reason"
72                 stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
73                 stat.message = "0x%02x" % reset
74
75                 stat.values.append(KeyValue("Watchdog Reset Flag", str(bool(reset & (1 << 3)))))
76                 stat.values.append(KeyValue("Brown-out Reset Flag", str(bool(reset & (1 << 2)))))
77                 stat.values.append(KeyValue("External Reset Flag", str(bool(reset & (1 << 1)))))
78                 stat.values.append(KeyValue("Power-on Reset Flag", str(bool(reset & (1 << 0)))))
79
80                 msg.status.append(stat)
81                 self.pub_diag.publish(msg)
82                 return reset
83
84
85         def get_tle_err(self):
86                 err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
87                 
88                 msg = DiagnosticArray()
89                 msg.header.stamp = rospy.Time.now()
90                 stat = DiagnosticStatus()
91                 stat.name = "Motor: Error Status"
92                 stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
93                 stat.message = "0x%02x" % err
94
95                 stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
96                 stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
97                 stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
98                 stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
99
100                 msg.status.append(stat)
101                 self.pub_diag.publish(msg)
102         
103         def get_voltage(self):
104                 volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
105
106                 msg = DiagnosticArray()
107                 msg.header.stamp = rospy.Time.now()
108                 stat = DiagnosticStatus()
109                 stat.name = "Voltage"
110                 stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
111                 stat.message = "%.2fV" % volt
112
113                 msg.status.append(stat)
114                 self.pub_diag.publish(msg)
115
116
117         def get_odom(self):
118                 posx, posy, angle = struct.unpack(">fff", i2c_read_reg(0x50, 0x40, 12))
119                 speed_trans, speed_rot = struct.unpack(">ff", i2c_read_reg(0x50, 0x38, 8))
120                 current_time = rospy.Time.now()
121
122                 # since all odometry is 6DOF we'll need a quaternion created from yaw
123                 odom_quat = tf.transformations.quaternion_from_euler(0, 0, angle)
124
125                 # first, we'll publish the transform over tf
126                 if self.tf_broadcaster is not None:
127                         self.tf_broadcaster.sendTransform((posx, posy, 0.0), odom_quat, current_time, "base_footprint", "odom")
128
129                 # next, we'll publish the odometry message over ROS
130                 odom = Odometry()
131                 odom.header.stamp = current_time
132                 odom.header.frame_id = "/odom"
133
134                 # set the position
135                 odom.pose.pose.position.x = posx
136                 odom.pose.pose.position.y = posy
137                 odom.pose.pose.position.z = 0.0
138                 odom.pose.pose.orientation.x = odom_quat[0]
139                 odom.pose.pose.orientation.y = odom_quat[1]
140                 odom.pose.pose.orientation.z = odom_quat[2]
141                 odom.pose.pose.orientation.w = odom_quat[3]
142                 odom.pose.covariance[0] = 1e-3 # x
143                 odom.pose.covariance[7] = 1e-3 # y
144                 odom.pose.covariance[14] = 1e6 # z
145                 odom.pose.covariance[21] = 1e6 # rotation about X axis
146                 odom.pose.covariance[28] = 1e6 # rotation about Y axis
147                 odom.pose.covariance[35] = 0.1 # rotation about Z axis
148
149                 # set the velocity
150                 odom.child_frame_id = "base_footprint"
151                 odom.twist.twist.linear.x = speed_trans
152                 odom.twist.twist.linear.y = 0.0
153                 odom.twist.twist.angular.z = speed_rot
154                 odom.twist.covariance[0] = 1e-3 # x
155                 odom.twist.covariance[7] = 1e-3 # y
156                 odom.twist.covariance[14] = 1e6 # z
157                 odom.twist.covariance[21] = 1e6 # rotation about X axis
158                 odom.twist.covariance[28] = 1e6 # rotation about Y axis
159                 odom.twist.covariance[35] = 0.1 # rotation about Z axis
160
161                 # publish the message
162                 self.pub_odom.publish(odom)
163
164         
165         def set_speed(self, trans, rot):
166                 i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot))
167
168         def cmdVelReceived(self, msg):
169                 trans = msg.linear.x
170                 rot = msg.angular.z # rad/s
171                 self.set_speed(trans, rot)
172
173         # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12
174         def get_dist_ir(self, num):
175                 dev = i2c(0x52)
176                 s = struct.pack("B", num)
177                 dev.write(s)
178                 dev.close()
179
180                 sleep(2e-6)
181
182                 dev = i2c(0x52)
183                 s = dev.read(2)
184                 dev.close()
185
186                 val = struct.unpack(">H", s)[0]
187                 return 15221/(val - -276.42)/100;
188         
189         def get_dist_srf(self, num):
190                 dev = i2c(0x52)
191                 s = struct.pack("B", num)
192                 dev.write(s)
193                 dev.close()
194
195                 sleep(50e-3)
196
197                 dev = i2c(0x52)
198                 s = dev.read(2)
199                 dev.close()
200
201                 return struct.unpack(">H", s)[0]/1000.0
202
203         def get_dist_left(self):
204                 dist = self.get_dist_ir(0x1)
205
206         def get_dist_right(self):
207                  dist = self.get_dist_ir(0x3)
208
209         def get_dist_forward(self):
210                 dist = self.get_dist_srf(0x5)
211
212         def get_dist_backward(self):
213                 dist = self.get_dist_srf(0x7)
214
215
216 if __name__ == "__main__":
217         MoveBase()