X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=5215d49ca5d3e7dd68fb751181f0fac9d8f197cd;hp=50cde9f5af3b10b75281767562a0924bd14747c5;hb=1bb8d565837691d68b3d674463be10de3330c2da;hpb=5423512c8fb51feb2fa1348a9dc2b606dc7af377 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 50cde9f..5215d49 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -12,9 +12,9 @@ from math import * from geometry_msgs.msg import Twist from nav_msgs.msg import Odometry from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue +from dynamic_reconfigure.server import Server from sensor_msgs.msg import Imu, Range from wild_thumper.msg import LedStripe -from dynamic_reconfigure.server import Server from wild_thumper.cfg import WildThumperConfig WHEEL_DIST = 0.248 @@ -31,7 +31,7 @@ class LPD8806: self.update() def set(self, i, red=0, green=0, blue=0): - if red > 127 or green > 127 or blue >> 127 or red < 0 or green < 0 or blue < 0: + if red > 127 or green > 127 or blue > 127 or red < 0 or green < 0 or blue < 0: raise Exception("Bad RGB Value") self.l[i] = (red, green, blue) @@ -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 @@ -255,7 +255,7 @@ class MoveBase: def cmdVelReceived(self, msg): if not self.bMotorManual: - rospy.logdebug("Set new cmd_vel:", msg.linear.x, msg.angular.z) + rospy.logdebug("Set new cmd_vel: %.2f %.2f", msg.linear.x, msg.angular.z) self.cmd_vel = (msg.linear.x, msg.angular.z) # commit speed on next update cycle rospy.logdebug("Set new cmd_vel done") @@ -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: