import rospy
from turtlesim.msg import Pose
from nav_msgs.msg import Odometry
from tf.transformations import euler_from_quaternion
from math import degrees, pi
class TB3Pose2D:
def __init__(self):
rospy.init_node('pub_tb3_pose', anonymous = True)
rospy.Subscriber('/odom', Odometry, self.get_odom)
self.pub = rospy.Publisher('/tb3pose', Pose, queue_size = 10)
self.tb3pose2d = Pose()
self.previous_angle = 0.0
self.angular_displacement = 0.0
def get_odom(self, dat):
pos_x, pos_y, current_angle = self.get_pose(dat)
pose2d = Pose()
pose2d.x = pos_x
pose2d.y = pos_y
pose2d.linear_velocity = dat.twist.twist.linear.x
pose2d.angular_velocity = dat.twist.twist.angular.z
delta_angle = current_angle - self.previous_angle
if delta_angle > 5.0:
delta_angle -= 2 * pi
elif delta_angle < -5.0:
delta_angle += 2 * pi
else:
pass
self.previous_angle = current_angle
self.angular_displacement += delta_angle
pose2d.theta = self.angular_displacement
self.tb3pose2d = pose2d; self.pub.publish(self.tb3pose2d)
def get_pose(self, msg):
q = (msg.pose.pose.orientation.x, msg.pose.pose.orientation.y,
msg.pose.pose.orientation.z, msg.pose.pose.orientation.w)
quart = euler_from_quaternion(q)
theta = quart[2]
if theta < 0:
theta += 2 * pi
pos_x = msg.pose.pose.position.x
pos_y = msg.pose.pose.position.y
return pos_x, pos_y, theta
if __name__ == '__main__':
try:
TB3Pose2D()
rospy.spin()
except rospy.ROSInterruptException: pass