Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
Now publishing cleaned values
  • Loading branch information
ret15108 committed Feb 9, 2018
1 parent db0e192 commit bf9f492
Showing 1 changed file with 22 additions and 0 deletions.
22 changes: 22 additions & 0 deletions src/imu_cleaning.py
Expand Up @@ -2,9 +2,29 @@
import rospy
from geometry_msgs.msg import Quaternion, Vector3
from sensor_msgs.msg import Imu
from std_msgs.msg import *

import math

class VariableMaintainer():
def __init__(self):
self._time = rospy.Time.now()

@property
def time(self):
return self._time

@time.setter
def time(self, value):
self._time = value

def publishCleanImu(msg, correctionVector):
pub = rospy.Publisher('clean_imu',Imu)
msg.linear_acceleration.x -= correctionVector[0]
msg.linear_acceleration.y -= correctionVector[1]
msg.linear_acceleration.y -= correctionVector[2]
pub.publish(msg)

def main():
# Collect first 50 entries and average them.
rospy.init_node("imu_cleaner")
Expand All @@ -17,6 +37,8 @@ def main():
averages = map(lambda x: x/50,totals)
print(averages)
print("Magnitude is:", math.sqrt(math.pow(averages[0],2)+math.pow(averages[1],2)+math.pow(averages[2],2)))
rospy.Subscriber('imu', Imu, publishCleanImu, averages)
rospy.spin()

if __name__=='__main__':
main()

0 comments on commit bf9f492

Please sign in to comment.