Skip to content

Commit

Permalink
the stable branch cleaned
Browse files Browse the repository at this point in the history
  • Loading branch information
rishabhagarwal880 committed Nov 15, 2017
1 parent 33bd1f5 commit 5fbc75e
Showing 1 changed file with 4 additions and 13 deletions.
17 changes: 4 additions & 13 deletions src/shear_sensor/src/filter_cap.py
Original file line number Diff line number Diff line change
@@ -1,20 +1,17 @@
#!/usr/bin/env python
import rospy
import matplotlib.pyplot as plt
from std_msgs.msg import String
from std_msgs.msg import Float64
import builtins
import collections
from scipy.signal import savgol_filter
import numpy as np
from std_msgs.msg import String
from std_msgs.msg import Float64
from scipy.signal import savgol_filter

# create the list of capacitance
cap_list=collections.deque(maxlen=20)
cap_list_mean=collections.deque(maxlen=200)

#plt.axis([0, 10, 0, 1])
#plt.ion()

# float capacitance
capacitance = 100.00
mean_cap = 100.00
Expand All @@ -23,27 +20,21 @@
pub_cap = rospy.Publisher('capacitance_val', Float64)
pub_mean = rospy.Publisher('mean_cap', Float64)

#count = 1
def callback(data):
# global count
# Create the list to filter and calculate mean
cap_list.append(data.data/100000)
if len(cap_list) < 20 :
capacitance = cap_list[-1]
else :
# Savitzky Golay filter for continuous stream of data
y = savgol_filter(cap_list, 15, 2)
# p= savgol_filter(cap_list, 19, 2)
cap_list_mean.append(y[-1])
capacitance = y[-1]
pub_cap.publish(Float64(capacitance))
if len(cap_list_mean) == 200 :
mean_cap = np.mean(cap_list_mean)
pub_mean.publish(Float64(mean_cap))
#count = count + 1
#plt.plot(count,capacitance,'r--',count, mean_cap,'bs')
#plt.pause(0.05)
rospy.loginfo("capacitance value %s", capacitance)
rospy.loginfo("capacitance %s and mean %s" % (capacitance, mean_cap))

def listener():

Expand Down

0 comments on commit 5fbc75e

Please sign in to comment.