X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=5fc59d7dbf5dad1dfd63639fa267534032073aa4;hp=7254c1d38ad4573961862f0af7850e87872d417b;hb=d44edcac9dd285abbd1a6b2f9f82b6d15be00ff6;hpb=cc73472b4a28a4ea6a97d96621b3ca260be01098 diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 7254c1d..5fc59d7 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -71,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): @@ -102,6 +102,15 @@ class MoveBase: 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 = 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 @@ -112,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] @@ -212,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)