X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fmove_base.py;fp=scripts%2Fmove_base.py;h=0beaf2668801f27a7a66a1a0a54a755b755646bd;hp=6c066f391f9b50a70c24f2a77a8ac335894f263b;hb=37ec2a1056b61c00cefc44bca9bb5eb7d782a6e1;hpb=bd5ce223f2fe077a697352c44a366a33d1f692f0 diff --git a/scripts/move_base.py b/scripts/move_base.py index 6c066f3..0beaf26 100755 --- a/scripts/move_base.py +++ b/scripts/move_base.py @@ -24,6 +24,7 @@ class MoveBase: self.set_speed(0, 0) rospy.loginfo("Init done") i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction + self.handicap_last = (-1, -1) self.run() def run(self): @@ -42,18 +43,18 @@ class MoveBase: rate.sleep() def set_motor_handicap(self, front, aft): # percent - i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft)) + if self.handicap_last != (front, aft): + i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft)) + self.handicap_last = (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) + val = (100.0/65)*abs(pitch)*180/pi + self.set_motor_handicap(0, int(val)) elif pitch < -30*pi/180: - val = (100/90)*abs(pitch)*180/pi - print "front handicap", val - self.set_motor_handicap(val, 0) + val = (100.0/65)*abs(pitch)*180/pi + self.set_motor_handicap(int(val), 0) else: self.set_motor_handicap(0, 0)