new_method.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 #   http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 
00017 
00018 import rospy
00019 from cob_msgs.msg import EmergencyStopState
00020 from std_msgs.msg import Float64
00021 import savizky
00022 
00023 class volts_filter():
00024 
00025     def __init__(self):
00026         self.volts = 0.
00027         self.wsize = 61
00028         self.filter_order = 3
00029         self.theta = rospy.get_param("theta")
00030         self.off_y = rospy.get_param("off_y")
00031         self.abcd = rospy.get_param("abcd")
00032         self.hvalue = 0
00033         self.sg = savitzky.savitzky_golay(window_size=wsize, order=filter_order)
00034         self.volt_filt = None
00035 
00036         rospy.Subscriber("/power_board/voltage", Float64, callback)
00037 
00038     def callback(self, data):
00039 
00040         if(self.hvalue == 0):
00041             self.hvalue = data
00042             self.volt_filt = hvalue*np.ones(2*wsize+1)
00043 
00044             if(data <= 44000):
00045                 self.volts = 44000
00046             time_r = 0.
00047             return
00048         elif(data >= 48000):
00049                 self.volts = 48000
00050 
00051         else:
00052             self.volts = data
00053 
00054         self.volt_filt = np.insert(self.volt_filt, 0, self.volts)
00055         self.volt_filt = np.delete(self.volt_filt, -1)
00056 
00057         vfilt = sg.filter(volt_filt)
00058         old_settings = np.seterr(all='raise')
00059 
00060         self.t_est = np.polyval(self.abcd, self.vfilt[self.wsize])
00061 
00062         self.t_est = vfilt[self.wsize]*sin(self.theta) + self.t_est*cos(self.theta)
00063 
00064         self.t_est = self.t_est + off_y
00065 
00066 
00067 if __name__ == '__main__':
00068     rospy.init_node('volt_filt')
00069     vf = volts_filter()
00070 
00071     while not rospy.is_shutdown():
00072         rospy.sleep(1.0)
00073 
00074 


cob_relayboard
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:18