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)
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:
msg.status.append(stat)
self.pub_diag.publish(msg)
+ 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))
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
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.start_dist_srf(0x5) # get next value
+
+ 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)
- self.start_dist_srf(0xb) # get next value
+
+ 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: