imu_monitor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 import PyKDL
5 from sensor_msgs.msg import Imu
6 from pr2_mechanism_controllers.msg import Odometer
7 from threading import Lock
8 from math import fabs, pi
9 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus, KeyValue
10 
11 EPS = 0.0001
12 
13 class ImuMonitor:
14  def __init__(self):
15  self.lock = Lock()
16 
17  # reset state
18  self.dist = 0.0
19  self.drift = -1.0
20  self.last_angle = 0.0
21  self.start_angle = 0.0
22  self.start_time = rospy.Time.now()
23 
24  # subscribe to topics
25  self.imu_sub = rospy.Subscriber('torso_lift_imu/data', Imu, self.imu_cb)
26  self.odom_sub = rospy.Subscriber('base_odometry/odometer', Odometer, self.odom_cb)
27 
28  # diagnostics
29  self.pub_diag = rospy.Publisher('/diagnostics', DiagnosticArray, queue_size= 1)
30 
31  self.diag_timer = rospy.Timer(rospy.Duration(1), self.publish_diagnostics)
32 
33 
34  def imu_cb(self, msg):
35  with self.lock:
36  rot = PyKDL.Rotation.Quaternion(msg.orientation.x, msg.orientation.y,
37  msg.orientation.z, msg.orientation.w)
38  (r, p, self.last_angle) = rot.GetRPY()
39 
40  def odom_cb(self, msg):
41  with self.lock:
42  dist = msg.distance + (msg.angle * 0.25)
43 
44  # check if base moved
45  if dist > self.dist + EPS:
46  self.start_time = rospy.Time.now()
47  self.start_angle = self.last_angle
48  self.dist = dist
49 
50  # do imu test if possible
51  if rospy.Time.now() > self.start_time + rospy.Duration(10.0):
52  self.drift = fabs(self.start_angle - self.last_angle)*180/(pi*10)
53  self.start_time = rospy.Time.now()
54  self.start_angle = self.last_angle
55  self.last_measured = rospy.Time.now()
56 
57  def publish_diagnostics(self, event):
58  with self.lock:
59  # publish diagnostics
60  d = DiagnosticArray()
61  d.header.stamp = rospy.Time.now()
62  ds = DiagnosticStatus()
63  ds.name = "imu_node: Imu Drift Monitor"
64  if self.drift < 0.5:
65  ds.level = DiagnosticStatus.OK
66  ds.message = 'OK'
67  elif self.drift < 1.0:
68  ds.level = DiagnosticStatus.WARN
69  ds.message = 'Drifting'
70  else:
71  ds.level = DiagnosticStatus.ERROR
72  ds.message = 'Drifting'
73  drift = self.drift
74  if self.drift < 0:
75  last_measured = 'No measurements yet, waiting for base to stop moving before measuring'
76  drift = 'N/A'
77  else:
78  age = (rospy.Time.now() - self.last_measured).to_sec()
79  if age < 60:
80  last_measured = '%f seconds ago'%age
81  elif age < 3600:
82  last_measured = '%f minutes ago'%(age/60)
83  else:
84  last_measured = '%f hours ago'%(age/3600)
85  ds.values = [
86  KeyValue('Last measured', last_measured),
87  KeyValue('Drift (deg/sec)', str(drift)) ]
88  d.status = [ds]
89  self.pub_diag.publish(d)
90 
91 def main():
92  rospy.init_node('imu_monitor')
93  rospy.sleep(0.001) # init time
94 
95  monitor = ImuMonitor()
96 
97  rospy.spin()
98 
99 
100 if __name__ == '__main__':
101  main()
def odom_cb(self, msg)
Definition: imu_monitor.py:40
def publish_diagnostics(self, event)
Definition: imu_monitor.py:57
def imu_cb(self, msg)
Definition: imu_monitor.py:34
def main()
Definition: imu_monitor.py:91


imu_monitor
Author(s): Wim Meeussen
autogenerated on Fri Mar 24 2023 02:28:20