timestamp_alignment.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 from __future__ import print_function, division
3 import rospy
4 
5 import sensor_msgs.msg
6 from dynamic_reconfigure.server import Server
7 from hector_timestamp_alignment.cfg import timestamp_alignmentConfig
8 
10  def __init__(self, verbose):
11  self.imu_sub = rospy.Subscriber("/imu/data_original", sensor_msgs.msg.Imu, self.imu_cb)
12  self.imu_aligned_pub = rospy.Publisher("/imu/data", sensor_msgs.msg.Imu, queue_size=10)
13  self.srv = Server(timestamp_alignmentConfig, self.dynamic_reconfigure_cb)
14  self.delay = 0.00
15 
16  def imu_cb(self, imu_msg):
17  #print("Before: ", imu_msg.header.stamp)
18  imu_msg.header.stamp = imu_msg.header.stamp + rospy.Duration(self.delay)
19  #print("After: ", imu_msg.header.stamp)
20  self.imu_aligned_pub.publish(imu_msg)
21 
22  def dynamic_reconfigure_cb(self, config, level):
23  print(config.imu_offset)
24  self.delay = config.imu_offset
25  return config
26 
27 
28 if __name__ == "__main__":
29  rospy.init_node("timestamp_alignment_node")
30  hazmat_detection = TimestampAlignment(verbose=False)
31  while not rospy.is_shutdown():
32  rospy.spin()


hector_timestamp_alignment
Author(s):
autogenerated on Mon Jun 10 2019 13:34:53