X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=781acfa593abd636ffb8d9d339026462c62da9d1;hp=3d1c972ea43a6eaf3c0bef5e4e2ad390f847b8e4;hb=69de58605413a7ab335413874ff9dd89f2b6e21a;hpb=8786ef14dfb5b65efa0a260d91e569aa819aac14 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 3d1c972..781acfa 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -14,6 +14,8 @@ from nav_msgs.msg import Odometry from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue 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 @@ -55,6 +57,7 @@ class MoveBase: self.tf_broadcaster = tf.broadcaster.TransformBroadcaster() else: self.tf_broadcaster = None + 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) @@ -68,8 +71,8 @@ class MoveBase: self.handicap_last = (-1, -1) self.pStripe = LPD8806(1, 0, 12) rospy.Subscriber("cmd_vel_out", Twist, self.cmdVelReceived) - #rospy.Subscriber("imu", Imu, self.imuReceived) rospy.Subscriber("led_stripe", LedStripe, self.led_stripe_received) + rospy.Subscriber("imu", Imu, self.imuReceived) self.run() def run(self): @@ -79,6 +82,7 @@ class MoveBase: rospy.loginfo("Reset Status: 0x%x" % reset_val) i = 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() @@ -95,6 +99,20 @@ class MoveBase: self.cmd_vel = None rate.sleep() + def execute_dyn_reconf(self, config, level): + self.bClipRangeSensor = config["range_sensor_clip"] + self.range_sensor_max = config["range_sensor_max"] + self.odom_covar_xy = config["odom_covar_xy"] + self.odom_covar_angle = config["odom_covar_angle"] + self.pitch_handicap_enable = config["pitch_handicap_enable"] + self.pitch_handicap_limit = config["pitch_handicap_limit"] + self.pitch_handicap_strength = 100-config["pitch_handicap_strength"] + + if not self.pitch_handicap_enable: + self.set_motor_handicap(0, 0) + + return config + def set_motor_handicap(self, front, aft): # percent if front > 100: front = 100 if aft > 100: aft = 100 @@ -103,15 +121,16 @@ class MoveBase: self.handicap_last = (front, aft) def imuReceived(self, msg): - (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__()) - if pitch > 30*pi/180: - val = (100.0/60)*abs(pitch)*180/pi - self.set_motor_handicap(int(val), 0) - elif pitch < -30*pi/180: - val = (100.0/60)*abs(pitch)*180/pi - self.set_motor_handicap(0, int(val)) - else: - self.set_motor_handicap(0, 0) + if self.pitch_handicap_enable: + (roll, pitch, yaw) = tf.transformations.euler_from_quaternion(msg.orientation.__getstate__()) + if pitch > self.pitch_handicap_limit*pi/180: + val = (100.0/self.pitch_handicap_strength)*abs(pitch)*180/pi + self.set_motor_handicap(int(val), 0) + elif pitch < -self.pitch_handicap_limit*pi/180: + val = (100.0/self.pitch_handicap_strength)*abs(pitch)*180/pi + self.set_motor_handicap(0, int(val)) + else: + self.set_motor_handicap(0, 0) def get_reset(self): reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0] @@ -203,24 +222,19 @@ class MoveBase: odom.pose.pose.orientation.y = odom_quat[1] odom.pose.pose.orientation.z = odom_quat[2] odom.pose.pose.orientation.w = odom_quat[3] - odom.pose.covariance[0] = 1e-3 # x - odom.pose.covariance[7] = 1e-3 # y - odom.pose.covariance[14] = 1e6 # z - odom.pose.covariance[21] = 1e6 # rotation about X axis - odom.pose.covariance[28] = 1e6 # rotation about Y axis - odom.pose.covariance[35] = 0.03 # rotation about Z axis + 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[35] = self.odom_covar_angle # rotation about Z axis # set the velocity odom.child_frame_id = "base_footprint" odom.twist.twist.linear.x = speed_trans odom.twist.twist.linear.y = 0.0 odom.twist.twist.angular.z = speed_rot - odom.twist.covariance[0] = 1e-3 # x - odom.twist.covariance[7] = 1e-3 # y - odom.twist.covariance[14] = 1e6 # z - odom.twist.covariance[21] = 1e6 # rotation about X axis - odom.twist.covariance[28] = 1e6 # rotation about Y axis - odom.twist.covariance[35] = 0.03 # rotation about Z axis + odom.twist.covariance = odom.pose.covariance # publish the message self.pub_odom.publish(odom) @@ -230,7 +244,9 @@ class MoveBase: i2c_write_reg(0x50, 0x50, struct.pack(">ff", trans, rot)) def cmdVelReceived(self, msg): + rospy.logdebug("Set new cmd_vel:", 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") # http://rn-wissen.de/wiki/index.php/Sensorarten#Sharp_GP2D12 def get_dist_ir(self, num): @@ -258,6 +274,8 @@ class MoveBase: return struct.unpack(">H", i2c_read_reg(0x52, num, 2))[0]/1000.0 def send_range(self, pub, frame_id, typ, dist, min_range, max_range, fov_deg): + if self.bClipRangeSensor and dist > max_range: + dist = max_range msg = Range() msg.header.stamp = rospy.Time.now() msg.header.frame_id = frame_id @@ -283,13 +301,13 @@ class MoveBase: def get_dist_forward(self): if self.pub_range_fwd.get_num_connections() > 0: dist = self.read_dist_srf(0x15) - self.send_range(self.pub_range_fwd, "sonar_forward", Range.ULTRASOUND, dist, 0.04, 6, 40) + 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 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, 6, 40) + 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 led_stripe_received(self, msg):