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
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)
29 self.
pub_diag = rospy.Publisher(
'/diagnostics', DiagnosticArray, queue_size= 1)
36 rot = PyKDL.Rotation.Quaternion(msg.orientation.x, msg.orientation.y,
37 msg.orientation.z, msg.orientation.w)
42 dist = msg.distance + (msg.angle * 0.25)
45 if dist > self.
dist + EPS:
51 if rospy.Time.now() > self.
start_time + rospy.Duration(10.0):
61 d.header.stamp = rospy.Time.now()
62 ds = DiagnosticStatus()
63 ds.name =
"imu_node: Imu Drift Monitor"
65 ds.level = DiagnosticStatus.OK
67 elif self.
drift < 1.0:
68 ds.level = DiagnosticStatus.WARN
69 ds.message =
'Drifting'
71 ds.level = DiagnosticStatus.ERROR
72 ds.message =
'Drifting'
75 last_measured =
'No measurements yet, waiting for base to stop moving before measuring'
80 last_measured =
'%f seconds ago'%age
82 last_measured =
'%f minutes ago'%(age/60)
84 last_measured =
'%f hours ago'%(age/3600)
86 KeyValue(
'Last measured', last_measured),
87 KeyValue(
'Drift (deg/sec)', str(drift)) ]
92 rospy.init_node(
'imu_monitor')
100 if __name__ ==
'__main__':