Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034 """
00035 This module handles voltage messages from the Arduino Mega 2560
00036 mounted on BWI segbots, publishing them as ROS
00037 smart_battery_msgs/SmartBatteryStatus messages.
00038 """
00039
00040
00041 from __future__ import absolute_import, print_function, unicode_literals
00042
00043 import re
00044
00045 import rospy
00046 from smart_battery_msgs.msg import SmartBatteryStatus
00047 from geometry_msgs.msg import Vector3
00048
00049
00050 class VoltmeterMessages(object):
00051 """ ROS message translation for UTexas BWI segbot voltage obtained
00052 from Arduino sensor. """
00053 def __init__(self):
00054 self.parser = re.compile(
00055 r'V(\d+(\.\d*)?|\.\d+)')
00056 """ Extracts voltage reading from the Arduino serial message.
00057 :returns: voltage data string reported, may be empty.
00058 """
00059 self.pub = rospy.Publisher('battery0', SmartBatteryStatus)
00060
00061 self.battery = SmartBatteryStatus(
00062 rate=float('nan'),
00063 charge=float('nan'),
00064 capacity=float('nan'),
00065 design_capacity=float('nan'),
00066 charge_state=SmartBatteryStatus.DISCHARGING,
00067 present=1)
00068
00069 def publish(self, serial_msg):
00070 """ Publish a ROS Range message for each reading.
00071
00072 :param serial_msg: voltage message from Arduino.
00073 :type serial_msg: str
00074
00075 TODO: publish /diagnostic message, too
00076 """
00077
00078
00079 readings = self.parser.match(serial_msg)
00080 if not readings:
00081 rospy.logwarn('Invalid voltage message: ' + serial_msg)
00082 return
00083
00084
00085 self.battery.header.stamp = rospy.Time.now()
00086 self.battery.voltage = float(readings.group(1))
00087 rospy.logdebug('voltage: ' + str(self.battery.voltage))
00088 self.pub.publish(self.battery)
00089
00090
00091 voltmeter = VoltmeterMessages()
00092 handler = voltmeter.publish
00093 """ This interface is called once for each voltage message received. """