- (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__())
- if pitch > 30*pi/180:
- val = (100.0/60)*abs(pitch)*180/pi
- self.set_motor_handicap(int(val), 0)
- elif pitch < -30*pi/180:
- val = (100.0/60)*abs(pitch)*180/pi
- self.set_motor_handicap(0, int(val))
- else:
- self.set_motor_handicap(0, 0)
+ if self.rollover_protect and (any(self.cur_vel) or self.bMotorManual):
+ (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, 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(">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
+ self.cmd_vel = (0, 0)
+ rospy.logwarn("Rollver protection done")