X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=b4bb8ebbf1e4671e347faacd16c088aad9c613fd;hp=afef56a431be239d70bc28bb8f31804f6b4eb834;hb=7407e894ef07408064eb1eeff0a4c4901dcd91f4;hpb=6f9283b6b41b8e5fcfd346170ba231c35e8b938c 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):