def _check_battery_state(_battery_acpi_path): """ @return LaptopChargeStatus """ if os.access(_battery_acpi_path, os.F_OK): o = slerp(_battery_acpi_path+'/state') else: raise Exception(_battery_acpi_path+' does not exist') batt_info = yaml.load(o) rv = LaptopChargeStatus() state = batt_info.get('charging state', 'discharging') rv.charge_state = state_to_val.get(state, 0) rv.rate = _strip_A(batt_info.get('present rate', '-1 mA')) if rv.charge_state == LaptopChargeStatus.DISCHARGING: rv.rate = math.copysign(rv.rate, -1) # Need to set discharging rate to negative rv.charge = _strip_Ah(batt_info.get('remaining capacity', '-1 mAh')) rv.voltage = _strip_V(batt_info.get('present voltage', '-1 mV')) rv.present = batt_info.get('present', False) rv.header.stamp = rospy.get_rostime() return rv
def __init__(self): self._mutex = threading.Lock() self._last_info_update = 0 self._last_state_update = 0 self._msg = LaptopChargeStatus() self._power_pub = rospy.Publisher('laptop_charge', LaptopChargeStatus, latch=True, queue_size=5) self._diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size=1) # Battery info self._batt_acpi_path = rospy.get_param('~acpi_path', "/proc/acpi/battery/BAT0") self._batt_design_capacity = 0 self._batt_last_full_capacity = 0 self._last_info_update = 0 self._batt_info_rate = 1 / 60.0 self._batt_info_thread = threading.Thread(target=self._check_batt_info) self._batt_info_thread.daemon = True self._batt_info_thread.start() # Battery state self._batt_state_rate = 1 / 5.0 self._batt_state_thread = threading.Thread(target=self._check_batt_state) self._batt_state_thread.daemon = True self._batt_state_thread.start()
def _check_battery_state(_battery_acpi_path): """ @return LaptopChargeStatus """ rv = LaptopChargeStatus() if _battery_acpi_path.startswith('/proc'): if os.access(_battery_acpi_path, os.F_OK): o = slerp(_battery_acpi_path+'/state') else: raise Exception(_battery_acpi_path+' does not exist') batt_info = yaml.load(o) state = batt_info.get('charging state', 'discharging') rv.charge_state = state_to_val.get(state, 0) rv.rate = _strip_A(batt_info.get('present rate', '-1 mA')) if rv.charge_state == LaptopChargeStatus.DISCHARGING: rv.rate = math.copysign(rv.rate, -1) # Need to set discharging rate to negative rv.charge = _strip_Ah(batt_info.get('remaining capacity', '-1 mAh')) # /energy_now rv.voltage = _strip_V(batt_info.get('present voltage', '-1 mV')) # /voltage_now rv.present = batt_info.get('present', False) # /present rv.header.stamp = rospy.get_rostime() else: # Charging state; make lowercase and remove trailing eol state = _read_string(_battery_acpi_path+'/status', 'discharging').lower().rstrip() rv.charge_state = state_to_val.get(state, 0) if os.path.exists(_battery_acpi_path + '/power_now'): rv.rate = _read_number(_battery_acpi_path + '/power_now')/10e5 else: rv.rate = _read_number(_battery_acpi_path + '/current_now')/10e5 if rv.charge_state == LaptopChargeStatus.DISCHARGING: rv.rate = math.copysign(rv.rate, -1) # Need to set discharging rate to negative if os.path.exists(_battery_acpi_path + '/energy_now'): rv.charge = _read_number(_battery_acpi_path + '/energy_now')/10e5 else: rv.charge = _read_number(_battery_acpi_path + '/charge_now')/10e5 rv.voltage = _read_number(_battery_acpi_path + '/voltage_now')/10e5 rv.present = _read_number(_battery_acpi_path + '/present') == 1 rv.header.stamp = rospy.get_rostime() return rv
def _check_battery_state(_battery_acpi_path): """ @return LaptopChargeStatus """ rv = LaptopChargeStatus() if _battery_acpi_path.startswith('/proc'): if os.access(_battery_acpi_path, os.F_OK): o = slerp(_battery_acpi_path + '/state') else: raise Exception(_battery_acpi_path + ' does not exist') batt_info = yaml.load(o) state = batt_info.get('charging state', 'discharging') rv.charge_state = state_to_val.get(state, 0) rv.rate = _strip_A(batt_info.get('present rate', '-1 mA')) if rv.charge_state == LaptopChargeStatus.DISCHARGING: rv.rate = math.copysign( rv.rate, -1) # Need to set discharging rate to negative rv.charge = _strip_Ah(batt_info.get('remaining capacity', '-1 mAh')) # /energy_now rv.voltage = _strip_V(batt_info.get('present voltage', '-1 mV')) # /voltage_now rv.present = batt_info.get('present', False) # /present rv.header.stamp = rospy.get_rostime() else: # Charging state; make lowercase and remove trailing eol state = _read_string(_battery_acpi_path + '/status', 'discharging').lower().rstrip() rv.charge_state = state_to_val.get(state, 0) if os.path.exists(_battery_acpi_path + '/power_now'): rv.rate = _read_number(_battery_acpi_path + '/power_now') / 10e5 else: rv.rate = _read_number(_battery_acpi_path + '/current_now') / 10e5 if rv.charge_state == LaptopChargeStatus.DISCHARGING: rv.rate = math.copysign( rv.rate, -1) # Need to set discharging rate to negative if os.path.exists(_battery_acpi_path + '/energy_now'): rv.charge = _read_number(_battery_acpi_path + '/energy_now') / 10e5 else: rv.charge = _read_number(_battery_acpi_path + '/charge_now') / 10e5 rv.voltage = _read_number(_battery_acpi_path + '/voltage_now') / 10e5 rv.present = _read_number(_battery_acpi_path + '/present') == 1 rv.header.stamp = rospy.get_rostime() return rv