InternalImuUnitConverter.py 2.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970
  1. #!/usr/bin/env python3
  2. import tf
  3. import rospy
  4. import math
  5. from sensor_msgs.msg import Imu
  6. class imu_rescaller:
  7. def __init__(self):
  8. self.unit_acc = 9.8
  9. self.orientation_avg_num = 3
  10. pub_topic_name = "/imu/data"
  11. sub_topic_name = "/livox/imu"
  12. self.pub = rospy.Publisher(pub_topic_name, Imu, queue_size = 200)
  13. rospy.Subscriber(sub_topic_name, Imu, self.callback)
  14. self.orientation_avg_count = 0
  15. self.imu_first_msg = Imu()
  16. self.imu_first_msg.linear_acceleration.x = 0
  17. self.imu_first_msg.linear_acceleration.y = 0
  18. self.imu_first_msg.linear_acceleration.z = 0
  19. def callback(self, imu):
  20. msg = Imu()
  21. msg = imu
  22. msg.linear_acceleration.x = imu.linear_acceleration.x * self.unit_acc
  23. msg.linear_acceleration.y = imu.linear_acceleration.y * self.unit_acc
  24. msg.linear_acceleration.z = imu.linear_acceleration.z * self.unit_acc
  25. if self.orientation_avg_count < self.orientation_avg_num:
  26. self.imu_first_msg.linear_acceleration.x += msg.linear_acceleration.x
  27. self.imu_first_msg.linear_acceleration.y += msg.linear_acceleration.y
  28. self.imu_first_msg.linear_acceleration.z += msg.linear_acceleration.z
  29. self.orientation_avg_count += 1
  30. if self.orientation_avg_count == self.orientation_avg_num:
  31. self.imu_first_msg.linear_acceleration.x /= self.orientation_avg_num
  32. self.imu_first_msg.linear_acceleration.y /= self.orientation_avg_num
  33. self.imu_first_msg.linear_acceleration.z /= self.orientation_avg_num
  34. ax = self.imu_first_msg.linear_acceleration.x
  35. ay = self.imu_first_msg.linear_acceleration.y
  36. az = self.imu_first_msg.linear_acceleration.z
  37. r = math.atan2(ay, az)
  38. p = math.atan2(-ax, math.sqrt(ay**2 + az**2))
  39. y = 0
  40. q = tf.transformations.quaternion_from_euler(r, p, y)
  41. self.imu_first_msg.orientation.x = q[0]
  42. self.imu_first_msg.orientation.y = q[1]
  43. self.imu_first_msg.orientation.z = q[2]
  44. self.imu_first_msg.orientation.w = q[3]
  45. else:
  46. msg.orientation = self.imu_first_msg.orientation
  47. self.pub.publish(msg)
  48. def main():
  49. rospy.init_node("rescale_imu")
  50. rescaller = imu_rescaller()
  51. rospy.spin()
  52. if __name__ == "__main__":
  53. main()