power_state_phidget.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import numpy as np
19 import rospy
20 from cob_msgs.msg import PowerState
21 from cob_phidgets.msg import AnalogSensor
22 
23 
25  PHIDGET_MAX_VALUE = 999
26  PHIDGET_MIN_VALUE = 0
27  PERIOD_RECORD_SIZE = 6
28  VOLTAGE_COLLECTION_TIME = 6.0 # sec
29 
30  def __init__(self):
31  self.voltage = None
32  self.current = None
33  self.last_update = rospy.Time(0)
34  self.charging = False
35  try:
36  self.voltage_divider_factor = rospy.get_param("~voltage_divider_factor")
37  except KeyError:
38  raise KeyError("Parameter \"~voltage_divider_factor\" not found on parameter server.")
39  self.voltage_full = rospy.get_param("~voltage_full", 52.0)
40  self.voltage_empty = rospy.get_param("~voltage_empty", 38.0)
41  self.current_max = rospy.get_param("~current_max", 30.0)
42  self.current_min = rospy.get_param("~current_min", -30.0)
43 
44  self.pub_power_state = rospy.Publisher('power_state', PowerState, queue_size=1)
45  self.sub_analog_sensors = rospy.Subscriber("analog_sensors", AnalogSensor, self.phidget_cb)
46 
47  self.pr_next = 0
48  self.period_record = []
49  self.cb_avg_time = 0.1
50  self.voltage_bag_maxlen = 100
51  self.voltage_bag = []
52 
53  def append_voltage_bag(self, num):
54  while len(self.voltage_bag) >= self.voltage_bag_maxlen:
55  self.voltage_bag.pop(0)
56  self.voltage_bag.append(num)
57 
58  def calculate_voltage(self):
59  if len(self.voltage_bag) > 0:
60  self.voltage = np.mean(self.voltage_bag)
61 
62  def phidget_cb(self, msg):
63  # Estimate commands frequency; we do continuously as it can be very different depending on the
64  # publisher type, and we don't want to impose extra constraints to keep this package flexible
65  if len(self.period_record) < self.PERIOD_RECORD_SIZE:
66  self.period_record.append((rospy.Time.now() - self.last_update).to_sec())
67  else:
68  self.period_record[self.pr_next] = (rospy.Time.now() - self.last_update).to_sec()
69 
70  self.pr_next += 1
71  self.pr_next %= len(self.period_record)
72  self.last_update = rospy.Time.now()
73 
74  if len(self.period_record) <= self.PERIOD_RECORD_SIZE / 2:
75  # wait until we have some values; make a reasonable assumption (10 Hz) meanwhile
76  self.cb_avg_time = 0.1
77  else:
78  # enough; recalculate with the latest input
79  self.cb_avg_time = np.median(self.period_record)
80 
81  # now set the max voltage bag size
83 
84  voltage_raw = None
85  current_raw = None
86 
87  for i in range(0, len(msg.uri)):
88  if msg.uri[i] == "voltage":
89  voltage_raw = msg.value[i]
90  if msg.uri[i] == "current":
91  current_raw = msg.value[i]
92 
93  if voltage_raw != None:
94  # Calculation of real voltage
95  voltage = self.voltage_divider_factor * voltage_raw / self.PHIDGET_MAX_VALUE
96  voltage = round(voltage, 3)
97  self.append_voltage_bag(voltage)
98 
99  if current_raw != None:
100  # Calculation of real current
101  self.current = self.current_min + (self.current_max - self.current_min) * (current_raw -
103  self.current = round(self.current, 3)
104 
105  if self.current > 0:
106  self.charging = True
107  else:
108  self.charging = False
109 
111  if not self.charging and self.voltage != None and self.current != None:
112  return round(self.voltage * abs(self.current), 3)
113  else:
114  return 0.0
115 
117  percentage = None
118  if self.voltage != None:
119  percentage = round((self.voltage - self.voltage_empty) * 100 / (self.voltage_full - self.voltage_empty), 3)
120  percentage = min(percentage, 100)
121  percentage = max(percentage, 0)
122  return percentage
123  else:
124  return 0.0
125 
126  def publish(self):
127  self.calculate_voltage()
128  if self.voltage != None and self.current != None and (rospy.Time.now() - self.last_update) < rospy.Duration(1):
129  ps = PowerState()
130  ps.header.stamp = self.last_update
131  ps.voltage = self.voltage
132  ps.current = self.current
133  ps.power_consumption = self.calculate_power_consumption()
134  ps.relative_remaining_capacity = self.calculate_relative_remaining_capacity()
135  ps.charging = self.charging
136  self.pub_power_state.publish(ps)
137 
138 if __name__ == "__main__":
139  rospy.init_node("power_state_phidget")
140  try:
142  except KeyError as e:
143  rospy.logerr("Shutting down: {}".format(e))
144  exit(1)
145 
146  rospy.loginfo("power state phidget running")
147  rate = rospy.Rate(10)
148  while not rospy.is_shutdown():
149  psp.publish()
150  rate.sleep()


cob_phidget_power_state
Author(s): Benjamin Maidel
autogenerated on Wed Apr 7 2021 02:11:45