From 7407e894ef07408064eb1eeff0a4c4901dcd91f4 Mon Sep 17 00:00:00 2001
From: Erik Andresen <erik@vontaene.de>
Date: Fri, 14 Apr 2017 09:46:44 +0200
Subject: [PATCH] Activate rollover protection only when moving and default to
 max pwm

---
 config/wt_node.cfg | 2 +-
 scripts/wt_node.py | 5 ++++-
 2 files changed, 5 insertions(+), 2 deletions(-)

diff --git a/config/wt_node.cfg b/config/wt_node.cfg
index 768363a..4217be7 100755
--- a/config/wt_node.cfg
+++ b/config/wt_node.cfg
@@ -10,6 +10,6 @@ gen.add("odom_covar_xy",	double_t,	0, "Odometry covariance: translation", 1e-2,
 gen.add("odom_covar_angle",	double_t,	0, "Odometry covariance: rotation", 0.25, 1e-6, 6.2832)
 gen.add("rollover_protect",	bool_t,		0, "Enable motor rollover protection on pitch", True)
 gen.add("rollover_protect_limit",double_t,	0, "Pitch rollover protection limit (degree)", 45, 0, 90)
-gen.add("rollover_protect_pwm",	double_t,	0, "Pitch rollover protection speed (pwm)", 100, 0, 255)
+gen.add("rollover_protect_pwm",	double_t,	0, "Pitch rollover protection speed (pwm)", 255, 0, 255)
 
 exit(gen.generate("wild_thumper", "wild_thumper", "WildThumper"))
diff --git a/scripts/wt_node.py b/scripts/wt_node.py
index afef56a..b4bb8eb 100755
--- a/scripts/wt_node.py
+++ b/scripts/wt_node.py
@@ -65,6 +65,7 @@ class MoveBase:
 		self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16)
 		self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16)
 		self.cmd_vel = None
+		self.cur_vel = (0, 0)
 		self.bMotorManual = False
 		self.set_speed(0, 0)
 		rospy.loginfo("Init done")
@@ -96,6 +97,7 @@ class MoveBase:
 			i+=1
 			if self.cmd_vel != None:
 				self.set_speed(self.cmd_vel[0], self.cmd_vel[1])
+				self.cur_vel = self.cmd_vel
 				self.cmd_vel = None
 			rate.sleep()
 
@@ -111,7 +113,7 @@ class MoveBase:
 		return config
 
 	def imuReceived(self, msg):
-		if self.rollover_protect:
+		if self.rollover_protect and any(self.cur_vel):
 			(roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
 			if pitch > self.rollover_protect_limit*pi/180:
 				self.bMotorManual = True
@@ -124,6 +126,7 @@ class MoveBase:
 			elif self.bMotorManual:
 				i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
 				self.bMotorManual = False
+				self.cmd_vel = (0, 0)
 				rospy.logwarn("Rollver protection done")
 
 	def get_reset(self):
-- 
2.39.5