]> defiant.homedns.org Git - ros_wild_thumper.git/blobdiff - scripts/wt_node.py
rollover protection: Also stop unused motors
[ros_wild_thumper.git] / scripts / wt_node.py
index 3d3adefb058a7d15d1bd70b6352004f187ecf018..afef56a431be239d70bc28bb8f31804f6b4eb834 100755 (executable)
@@ -115,15 +115,16 @@ class MoveBase:
                        (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
                        if pitch > self.rollover_protect_limit*pi/180:
                                self.bMotorManual = True
-                               i2c_write_reg(0x50, 0x3, struct.pack(">h", self.rollover_protect_pwm))
-                               i2c_write_reg(0x50, 0x7, struct.pack(">h", self.rollover_protect_pwm))
+                               i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm))
+                               rospy.logwarn("Running forward rollver protection")
                        elif pitch < -self.rollover_protect_limit*pi/180:
                                self.bMotorManual = True
-                               i2c_write_reg(0x50, 0x1, struct.pack(">h", -self.rollover_protect_pwm))
-                               i2c_write_reg(0x50, 0x5, struct.pack(">h", -self.rollover_protect_pwm))
+                               i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0))
+                               rospy.logwarn("Running backward rollver protection")
                        elif self.bMotorManual:
                                i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0))
                                self.bMotorManual = False
+                               rospy.logwarn("Rollver protection done")
 
        def get_reset(self):
                reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0]