From 1e0954c7b50dcb6211cfee54fda35cbb36cf6b40 Mon Sep 17 00:00:00 2001
From: Erik Andresen <erik@vontaene.de>
Date: Fri, 5 Jun 2015 17:22:48 +0000
Subject: [PATCH] move_base: use imu to control motor handicap

---
 launch/teleop.launch                          |  2 +-
 .../wild_thumper.launch                       |  2 ++
 scripts/move_base.py                          | 28 +++++++++++++++----
 3 files changed, 26 insertions(+), 6 deletions(-)
 rename wild_thumper.launch => launch/wild_thumper.launch (85%)

diff --git a/launch/teleop.launch b/launch/teleop.launch
index 4618895..5fb511c 100644
--- a/launch/teleop.launch
+++ b/launch/teleop.launch
@@ -1,6 +1,6 @@
 <?xml version="1.0"?>
 <launch>
-	<node pkg="turtlebot_teleop" type="turtlebot_teleop_joy" name="turtlebot_teleop_joystick">
+	<node pkg="turtlebot_teleop" type="turtlebot_teleop_joy" name="turtlebot_teleop_joystick" respawn="true">
 		<param name="scale_linear" value="0.2"/>
 		<param name="scale_angular" value="-0.2"/>
 		<param name="axis_deadman" value="3"/>
diff --git a/wild_thumper.launch b/launch/wild_thumper.launch
similarity index 85%
rename from wild_thumper.launch
rename to launch/wild_thumper.launch
index af52d92..42682bf 100644
--- a/wild_thumper.launch
+++ b/launch/wild_thumper.launch
@@ -11,4 +11,6 @@
 	<node pkg="razor_imu_9dof" type="imu_node.py" name="imu_node" output="screen">
 		<rosparam file="$(find wild_thumper)/cfg/razor.yaml" command="load"/>
 	</node>
+
+	<node pkg="wild_thumper" type="move_base.py" name="move_base" output="screen" respawn="true" />
 </launch>
diff --git a/scripts/move_base.py b/scripts/move_base.py
index 127bcca..6c066f3 100755
--- a/scripts/move_base.py
+++ b/scripts/move_base.py
@@ -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)
@@ -39,6 +41,22 @@ class MoveBase:
 			#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]
 
@@ -69,10 +87,10 @@ class MoveBase:
 		stat.level = DiagnosticStatus.ERROR if err else DiagnosticStatus.OK
 		stat.message = "0x%02x" % err
 
-		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)))))
+		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)))))
 
 		msg.status.append(stat)
 		self.pub_diag.publish(msg)
@@ -84,7 +102,7 @@ class MoveBase:
 		msg.header.stamp = rospy.Time.now()
 		stat = DiagnosticStatus()
 		stat.name = "Voltage"
-		stat.level = DiagnosticStatus.ERROR if volt < 6 else DiagnosticStatus.OK
+		stat.level = DiagnosticStatus.ERROR if volt < 7 else DiagnosticStatus.OK
 		stat.message = "%.2fV" % volt
 
 		msg.status.append(stat)
-- 
2.39.5