X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef;hp=5215d49ca5d3e7dd68fb751181f0fac9d8f197cd;hb=b301eb19e6487497a8bb946c538a25aa4ee28c1d;hpb=1bb8d565837691d68b3d674463be10de3330c2da diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 5215d49..1cf9d8d 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -100,12 +100,15 @@ class MoveBase: if sonar_count == 0: self.get_dist_forward_left() + self.update_dist_backward() sonar_count+=1 elif sonar_count == 1: self.get_dist_backward() + self.update_dist_forward_right() sonar_count+=1 elif sonar_count == 2: self.get_dist_forward_right() + self.update_dist_forward_left() sonar_count=0 if self.cmd_vel != None: @@ -234,9 +237,9 @@ class MoveBase: odom.pose.pose.orientation.w = odom_quat[3] odom.pose.covariance[0] = self.odom_covar_xy # x odom.pose.covariance[7] = self.odom_covar_xy # y - odom.pose.covariance[14] = 99999 # z - odom.pose.covariance[21] = 99999 # rotation about X axis - odom.pose.covariance[28] = 99999 # rotation about Y axis + odom.pose.covariance[14] = self.odom_covar_xy # z + odom.pose.covariance[21] = self.odom_covar_angle # rotation about X axis + odom.pose.covariance[28] = self.odom_covar_angle # rotation about Y axis odom.pose.covariance[35] = self.odom_covar_angle # rotation about Z axis # set the velocity @@ -313,19 +316,28 @@ class MoveBase: if self.pub_range_fwd_left.get_num_connections() > 0: dist = self.read_dist_srf(0x15) 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 update_dist_forward_left(self): + if self.pub_range_fwd_left.get_num_connections() > 0: + self.start_dist_srf(0x5) 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, self.range_sensor_max, 30) - self.start_dist_srf(0x7) # get next value + + def update_dist_backward(self): + if self.pub_range_bwd.get_num_connections() > 0: + self.start_dist_srf(0x7) 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_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30) - self.start_dist_srf(0xb) # get next value + + def update_dist_forward_right(self): + if self.pub_range_fwd_right.get_num_connections() > 0: + self.start_dist_srf(0xb) def led_stripe_received(self, msg): for led in msg.leds: