X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=5215d49ca5d3e7dd68fb751181f0fac9d8f197cd;hp=bbda8488780341b9167365e8b77c5cad3477cc18;hb=1bb8d565837691d68b3d674463be10de3330c2da;hpb=5b40ea26ccc4ab0276bd7dd37ab8cb8274299fe8;ds=sidebyside diff --git a/scripts/wt_node.py b/scripts/wt_node.py index bbda848..5215d49 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -96,11 +96,11 @@ class MoveBase: ir_count+=1 else: self.get_dist_right() - ir_count+=1 + ir_count=0 if sonar_count == 0: self.get_dist_forward_left() - sonar_count=0 + sonar_count+=1 elif sonar_count == 1: self.get_dist_backward() sonar_count+=1 @@ -312,7 +312,7 @@ class MoveBase: def get_dist_forward_left(self): if self.pub_range_fwd_left.get_num_connections() > 0: dist = self.read_dist_srf(0x15) - self.send_range(self.pub_range_fwd, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30) + self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30) self.start_dist_srf(0x5) # get next value def get_dist_backward(self): @@ -324,8 +324,8 @@ class MoveBase: def get_dist_forward_right(self): if self.pub_range_fwd_right.get_num_connections() > 0: dist = self.read_dist_srf(0x19) - self.send_range(self.pub_range_fwd, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30) - self.start_dist_srf(0x9) # get next value + self.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30) + self.start_dist_srf(0xb) # get next value def led_stripe_received(self, msg): for led in msg.leds: