]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/move_base.py
Merge branch 'master' of ssh://vontaene/home/erik_alt/git/ros_wild_thumper
[ros_wild_thumper.git] / scripts / move_base.py
index 0f0bc190fcd7030a6cbdf1b9824a93f309e7e689..6c066f391f9b50a70c24f2a77a8ac335894f263b 100755 (executable)
@@ -9,6 +9,7 @@ from math import *
 from geometry_msgs.msg import Twist
 from nav_msgs.msg import Odometry
 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
+from sensor_msgs.msg import Imu
 
 WHEEL_DIST = 0.248
 
@@ -16,6 +17,7 @@ class MoveBase:
        def __init__(self):
                rospy.init_node('wild_thumper_move_base')
                rospy.Subscriber("cmd_vel", Twist, self.cmdVelReceived)
+               rospy.Subscriber("imu", Imu, self.imuReceived)
                self.tf_broadcaster = tf.broadcaster.TransformBroadcaster()
                self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16)
                self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16)
@@ -26,29 +28,82 @@ class MoveBase:
        
        def run(self):
                rate = rospy.Rate(20.0)
+               reset_val = self.get_reset()
+               rospy.loginfo("Reset Status: 0x%x" % reset_val)
                while not rospy.is_shutdown():
+                       #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test
                        self.get_tle_err()
-                       #self.get_odom()
+                       self.get_odom()
+                       self.get_voltage()
                        #self.get_dist_forward()
                        #self.get_dist_backward()
                        #self.get_dist_left()
                        #self.get_dist_right()
                        rate.sleep()
 
+       def set_motor_handicap(self, front, aft): # percent
+               i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft))
+
+       def imuReceived(self, msg):
+               (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
+               if pitch > 30*pi/180:
+                       val = (100/90)*abs(pitch)*180/pi
+                       print "aft handicap", val
+                       self.set_motor_handicap(0, val)
+               elif pitch < -30*pi/180:
+                       val = (100/90)*abs(pitch)*180/pi
+                       print "front handicap", val
+                       self.set_motor_handicap(val, 0)
+               else:
+                       self.set_motor_handicap(0, 0)
+
+       def get_reset(self):
+               reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]
+
+               msg = DiagnosticArray()
+               msg.header.stamp = rospy.Time.now()
+               stat = DiagnosticStatus()
+               stat.name = "Reset reason"
+               stat.level = DiagnosticStatus.ERROR if reset & 0x0c else DiagnosticStatus.OK
+               stat.message = "0x%02x" % reset
+
+               stat.values.append(KeyValue("Watchdog Reset Flag", str(bool(reset & (1 << 3)))))
+               stat.values.append(KeyValue("Brown-out Reset Flag", str(bool(reset & (1 << 2)))))
+               stat.values.append(KeyValue("External Reset Flag", str(bool(reset & (1 << 1)))))
+               stat.values.append(KeyValue("Power-on Reset Flag", str(bool(reset & (1 << 0)))))
+
+               msg.status.append(stat)
+               self.pub_diag.publish(msg)
+               return reset
+
+
        def get_tle_err(self):
-               err = struct.unpack(">B", i2c_read_reg(0x50, 0x94, 1))[0]
+               err = struct.unpack(">B", i2c_read_reg(0x50, 0xA1, 1))[0]
                
                msg = DiagnosticArray()
                msg.header.stamp = rospy.Time.now()
                stat = DiagnosticStatus()
                stat.name = "Motor: Error Status"
-               stat.level = DiagnosticStatus.OK if not err else DiagnosticStatus.ERROR
-               stat.message = "OK" if not err else "Error"
+               stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
+               stat.message = "0x%02x" % err
+
+               stat.values.append(KeyValue("aft left", str(bool(err & (1 << 0)))))
+               stat.values.append(KeyValue("front left", str(bool(err & (1 << 1)))))
+               stat.values.append(KeyValue("front right", str(bool(err & (1 << 2)))))
+               stat.values.append(KeyValue("aft right", str(bool(err & (1 << 3)))))
 
-               stat.values.append(KeyValue("Motor 1", str(bool(err & (1 << 0)))))
-               stat.values.append(KeyValue("Motor 2", str(bool(err & (1 << 1)))))
-               stat.values.append(KeyValue("Motor 3", str(bool(err & (1 << 2)))))
-               stat.values.append(KeyValue("Motor 4", str(bool(err & (1 << 3)))))
+               msg.status.append(stat)
+               self.pub_diag.publish(msg)
+       
+       def get_voltage(self):
+               volt = struct.unpack(">h", i2c_read_reg(0x52, 0x09, 2))[0]/100.0
+
+               msg = DiagnosticArray()
+               msg.header.stamp = rospy.Time.now()
+               stat = DiagnosticStatus()
+               stat.name = "Voltage"
+               stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
+               stat.message = "%.2fV" % volt
 
                msg.status.append(stat)
                self.pub_diag.publish(msg)