X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=fcb20be43f2a8fd1795b19a66590a7c79ea70873;hp=b4bb8ebbf1e4671e347faacd16c088aad9c613fd;hb=d5421adc6fb7c85852a3b90b993742459ce03466;hpb=7407e894ef07408064eb1eeff0a4c4901dcd91f4 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index b4bb8eb..fcb20be 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) @@ -60,7 +60,8 @@ class MoveBase: self.dyn_conf = Server(WildThumperConfig, self.execute_dyn_reconf) self.pub_odom = rospy.Publisher("odom", Odometry, queue_size=16) self.pub_diag = rospy.Publisher("diagnostics", DiagnosticArray, queue_size=16) - self.pub_range_fwd = rospy.Publisher("range_forward", Range, queue_size=16) + self.pub_range_fwd_left = rospy.Publisher("range_forward_left", Range, queue_size=16) + self.pub_range_fwd_right = rospy.Publisher("range_forward_right", Range, queue_size=16) self.pub_range_bwd = rospy.Publisher("range_backward", Range, queue_size=16) self.pub_range_left = rospy.Publisher("range_left", Range, queue_size=16) self.pub_range_right = rospy.Publisher("range_right", Range, queue_size=16) @@ -81,20 +82,32 @@ class MoveBase: sleep(3) # wait 3s for ros to register and establish all subscriber connections before sending reset diag reset_val = self.get_reset() rospy.loginfo("Reset Status: 0x%x" % reset_val) - i = 0 + ir_count = 0 + sonar_count = 0 while not rospy.is_shutdown(): rospy.logdebug("Loop alive") #print struct.unpack(">B", i2c_read_reg(0x50, 0xA2, 1))[0] # count test self.get_motor_err() self.get_odom() self.get_voltage() - if i % 2: - self.get_dist_forward() + + if ir_count == 0: self.get_dist_left() + ir_count+=1 else: - self.get_dist_backward() self.get_dist_right() - i+=1 + ir_count=0 + + if sonar_count == 0: + self.get_dist_forward_left() + sonar_count+=1 + elif sonar_count == 1: + self.get_dist_backward() + sonar_count+=1 + elif sonar_count == 2: + self.get_dist_forward_right() + sonar_count=0 + if self.cmd_vel != None: self.set_speed(self.cmd_vel[0], self.cmd_vel[1]) self.cur_vel = self.cmd_vel @@ -242,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") @@ -296,10 +309,10 @@ class MoveBase: if dist > 69: self.send_range(self.pub_range_right, "ir_right", Range.INFRARED, 17.4/(dist - 69), 0.04, 0.3, 1) - def get_dist_forward(self): - if self.pub_range_fwd.get_num_connections() > 0: + 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", 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): @@ -307,6 +320,12 @@ class MoveBase: 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 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(0x9) # get next value def led_stripe_received(self, msg): for led in msg.leds: