X-Git-Url: https://defiant.homedns.org/gitweb/?p=ros_wild_thumper.git;a=blobdiff_plain;f=scripts%2Fwt_node.py;h=663a4f17774dbab88772e094c556f047246729a9;hp=1cf9d8d49fc42608ca1db0b1a0ed69873a95e4ef;hb=0b33908062c01bd1e6ee4b2b50229d7c83cbbb0c;hpb=b301eb19e6487497a8bb946c538a25aa4ee28c1d diff --git a/scripts/wt_node.py b/scripts/wt_node.py index 1cf9d8d..663a4f1 100755 --- a/scripts/wt_node.py +++ b/scripts/wt_node.py @@ -13,7 +13,7 @@ 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 sensor_msgs.msg import Imu, Range, BatteryState from wild_thumper.msg import LedStripe from wild_thumper.cfg import WildThumperConfig @@ -65,10 +65,12 @@ class MoveBase: 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.pub_battery = rospy.Publisher("battery", BatteryState, queue_size=16) self.cmd_vel = None self.cur_vel = (0, 0) self.bMotorManual = False self.set_speed(0, 0) + self.volt_last_warn = rospy.Time.now() rospy.loginfo("Init done") i2c_write_reg(0x50, 0x90, struct.pack("BB", 1, 1)) # switch direction self.pStripe = LPD8806(1, 0, 12) @@ -120,6 +122,7 @@ class MoveBase: def execute_dyn_reconf(self, config, level): self.bClipRangeSensor = config["range_sensor_clip"] self.range_sensor_max = config["range_sensor_max"] + self.range_sensor_fov = config["range_sensor_fov"] self.odom_covar_xy = config["odom_covar_xy"] self.odom_covar_angle = config["odom_covar_angle"] self.rollover_protect = config["rollover_protect"] @@ -210,6 +213,24 @@ class MoveBase: msg.status.append(stat) self.pub_diag.publish(msg) + if self.pub_battery.get_num_connections() > 0: + batmsg = BatteryState() + batmsg.header.stamp = rospy.Time.now() + batmsg.voltage = volt + batmsg.current = float('nan') + batmsg.charge = float('nan') + batmsg.capacity = float('nan') + batmsg.design_capacity = 5.0 + batmsg.percentage = float('nan') + batmsg.power_supply_status = BatteryState.POWER_SUPPLY_STATUS_DISCHARGING + batmsg.power_supply_health = BatteryState.POWER_SUPPLY_HEALTH_UNKNOWN + batmsg.power_supply_technology = BatteryState.POWER_SUPPLY_TECHNOLOGY_NIMH + self.pub_battery.publish(batmsg) + + if volt < 7 and (rospy.Time.now() - self.volt_last_warn).to_sec() > 10: + rospy.logerr("Voltage critical: %.2fV" % (volt)) + self.volt_last_warn = rospy.Time.now() + def get_odom(self): speed_trans, speed_rot, posx, posy, angle = struct.unpack(">fffff", i2c_read_reg(0x50, 0x38, 20)) @@ -246,6 +267,7 @@ class MoveBase: odom.child_frame_id = "base_footprint" odom.twist.twist.linear.x = speed_trans odom.twist.twist.linear.y = 0.0 + odom.twist.twist.linear.z = 0.0 odom.twist.twist.angular.z = speed_rot odom.twist.covariance = odom.pose.covariance @@ -315,7 +337,7 @@ class MoveBase: 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_left, "sonar_forward_left", 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, self.range_sensor_fov) def update_dist_forward_left(self): if self.pub_range_fwd_left.get_num_connections() > 0: @@ -324,7 +346,7 @@ class MoveBase: 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.send_range(self.pub_range_bwd, "sonar_backward", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov) def update_dist_backward(self): if self.pub_range_bwd.get_num_connections() > 0: @@ -333,7 +355,7 @@ class MoveBase: 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.send_range(self.pub_range_fwd_right, "sonar_forward_right", Range.ULTRASOUND, dist, 0.04, self.range_sensor_max, self.range_sensor_fov) def update_dist_forward_right(self): if self.pub_range_fwd_right.get_num_connections() > 0: