X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=3d3adefb058a7d15d1bd70b6352004f187ecf018;hp=7254c1d38ad4573961862f0af7850e87872d417b;hb=163e9fecf7bd83c737bd68b717ae47d174e93e12;hpb=c3307ab04ec14a48e15833c0894d9518d49613cf diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 7254c1d..3d3adef 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -65,14 +65,14 @@ class MoveBase: 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.bMotorManual = False self.set_speed(0, 0) rospy.loginfo("Init done") i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction - 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,25 +102,28 @@ class MoveBase: def execute_dyn_reconf(self, config, level): self.bClipRangeSensor = config["range_sensor_clip"] self.range_sensor_max = config["range_sensor_max"] - return config + self.odom_covar_xy = config["odom_covar_xy"] + self.odom_covar_angle = config["odom_covar_angle"] + self.rollover_protect = config["rollover_protect"] + self.rollover_protect_limit = config["rollover_protect_limit"] + self.rollover_protect_pwm = config["rollover_protect_pwm"] - def set_motor_handicap(self, front, aft): # percent - if front > 100: front = 100 - if aft > 100: aft = 100 - if self.handicap_last != (front, aft): - i2c_write_reg(0x50, 0x94, struct.pack(">bb", front, aft)) - self.handicap_last = (front, aft) + return config 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.rollover_protect: + (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)) + 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)) + elif self.bMotorManual: + i2c_write_reg(0x50, 0x1, struct.pack(">hhhh", 0, 0, 0, 0)) + self.bMotorManual = False def get_reset(self): reset = struct.unpack(">B", i2c_read_reg(0x50, 0xA0, 1))[0] @@ -212,24 +215,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) @@ -239,9 +237,10 @@ 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") + if not self.bMotorManual: + 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):