X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=dcae6740c02b7fa35e07eb7416f75293cc0819eb;hp=4064fb89a364ec91e9aaa7c9c5da2c8fe5607ade;hb=fb692fdbf76fda0e13adb284b6ccd09cb3fa7afb;hpb=53c52f19f4cd243c9f5a66780ca365d54820761f diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 4064fb8..dcae674 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -65,10 +65,10 @@ class MoveBase: (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__()) if pitch > 30*pi/180: val = (100.0/65)*abs(pitch)*180/pi - self.set_motor_handicap(0, int(val)) + self.set_motor_handicap(int(val), 0) elif pitch < -30*pi/180: val = (100.0/65)*abs(pitch)*180/pi - self.set_motor_handicap(int(val), 0) + self.set_motor_handicap(0, int(val)) else: self.set_motor_handicap(0, 0) @@ -238,13 +238,13 @@ class MoveBase: def get_dist_forward(self): if self.pub_range_fwd.get_num_connections() > 0: dist = self.read_dist_srf(0x15) - self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 30) + self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40) self.start_dist_srf(0x5) # get next value def get_dist_backward(self): if self.pub_range_bwd.get_num_connections() > 0: dist = self.read_dist_srf(0x17) - self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 30) + self.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, 6, 40) self.start_dist_srf(0x7) # get next value