savitzky_golay.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 from math import cos, sin
19 import numpy as np
20 
21 import rospy
22 import savitzky
23 from std_msgs.msg import Float64
24 from cob_msgs.msg import EmergencyStopState, PowerState
25 
26 class volts_filter():
27 
28  def __init__(self):
29  self.volts = 0.
30  self.wsize = 61
31  self.filter_order = 3
32  self.theta = rospy.get_param("~theta")
33  self.off_y = rospy.get_param("~off_y")
34  self.abcd = rospy.get_param("~abcd")
35  self.maximum_time = rospy.get_param("~maximum_time")
36  self.sg = savitzky.savitzky_golay(window_size=self.wsize, order=self.filter_order)
37  size = 2*self.wsize+1
38  self.volt_filt = 48000*np.ones(size)
39 
40  rospy.Subscriber("/power_board/voltage", Float64, self.callback)
41 
42  self.pub_power = rospy.Publisher('/power_state', PowerState, queue_size=1)
43  self.msg_power = PowerState()
44 
45  def callback(self, data):
46 
47  self.volts = data.data
48  self.volts = self.volts*1000
49 
50  if(self.volts <= 44000):
51  self.volts = 44000
52  elif(self.volts >= 48000):
53  self.volts = 48000
54 
55  self.process_voltage()
56 
57  def process_voltage(self):
58 
59  self.volt_filt = np.insert(self.volt_filt, 0, self.volts)
60  self.volt_filt = np.delete(self.volt_filt, -1)
61 
62  vfilt = self.sg.filter(self.volt_filt)
63 
64  old_settings = np.seterr(all='raise')
65 
66  self.t_est = np.polyval(self.abcd, vfilt[self.wsize])
67 
68  self.t_est = vfilt[self.wsize]*sin(self.theta) + self.t_est*cos(self.theta)
69  self.t_est = self.t_est + self.off_y
70 
71  if(self.t_est <0):
72  self.t_est = 0
73 
74  self.msg_power.header.stamp = rospy.Time.now()
75  self.msg_power.time_remaining.secs = self.t_est
76  #self.msg_power.prediction_method = '3rd_order_polynom'
77  #self.msg_power.relative_capacity = (self.t_est/self.maximum_time) * 100
78  #self.msg_power.AC_present = 0
79 
80  self.pub_power.publish(self.msg_power)
81 
82 if __name__ == '__main__':
83  rospy.init_node('volt_filt')
84  vf = volts_filter()
85 
86  while not rospy.is_shutdown():
87  rospy.sleep(1.0)


cob_voltage_control
Author(s): Alexander Bubeck
autogenerated on Wed Apr 7 2021 02:11:57