X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef;hp=3d3adefb058a7d15d1bd70b6352004f187ecf018;hb=b301eb19e6487497a8bb946c538a25aa4ee28c1d;hpb=163e9fecf7bd83c737bd68b717ae47d174e93e12 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 3d3adef..1cf9d8d 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,11 +60,13 @@ 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) self.cmd_vel = None + self.cur_vel = (0, 0) self.bMotorManual = False self.set_speed(0, 0) rospy.loginfo("Init done") @@ -80,22 +82,38 @@ 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() + 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: self.set_speed(self.cmd_vel[0], self.cmd_vel[1]) + self.cur_vel = self.cmd_vel self.cmd_vel = None rate.sleep() @@ -111,19 +129,21 @@ class MoveBase: return config def imuReceived(self, msg): - if self.rollover_protect: + if self.rollover_protect and any(self.cur_vel): (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__()) if pitch > self.rollover_protect_limit*pi/180: self.bMotorManual = True - i2c_write_reg(0x50, 0x3, struct.pack(">h", self.rollover_protect_pwm)) - i2c_write_reg(0x50, 0x7, struct.pack(">h", self.rollover_protect_pwm)) + i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, self.rollover_protect_pwm, 0, self.rollover_protect_pwm)) + rospy.logwarn("Running forward rollver protection") elif pitch < -self.rollover_protect_limit*pi/180: self.bMotorManual = True - i2c_write_reg(0x50, 0x1, struct.pack(">h", -self.rollover_protect_pwm)) - i2c_write_reg(0x50, 0x5, struct.pack(">h", -self.rollover_protect_pwm)) + i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", -self.rollover_protect_pwm, 0, -self.rollover_protect_pwm, 0)) + rospy.logwarn("Running backward rollver protection") elif self.bMotorManual: i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0)) self.bMotorManual = False + self.cmd_vel = (0, 0) + rospy.logwarn("Rollver protection done") def get_reset(self): reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0] @@ -217,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 @@ -238,7 +258,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") @@ -292,17 +312,32 @@ 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.start_dist_srf(0x5) # get next value + self.send_range(self.pub_range_fwd_left, "sonar_forward_left", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, 30) + + 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) + + 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: