Skip to content

Commit 8e0e924

Browse files
committed
Fix tf publishing bug
1 parent 4e2ff6a commit 8e0e924

File tree

1 file changed

+3
-37
lines changed

1 file changed

+3
-37
lines changed

cob_hardware_emulation/scripts/emulation_odom_laser.py

Lines changed: 3 additions & 37 deletions
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,7 @@
11
#!/usr/bin/env python
22

33
import argparse
4-
import copy
5-
import math
64
import rospy
7-
import tf
85
import tf2_ros
96
from geometry_msgs.msg import Twist, TransformStamped
107
from nav_msgs.msg import Odometry
@@ -31,55 +28,24 @@ def __init__(self, odom_frame):
3128

3229
self._transform_broadcaster = tf2_ros.TransformBroadcaster()
3330

34-
self._timestamp_last_update = rospy.Time.now()
35-
self._timestamp_last_odom = rospy.Time(0)
36-
3731
self._odom = Odometry()
3832
self._odom.header.frame_id = self._odom_frame
3933
self._odom.child_frame_id = "base_footprint"
4034
self._odom.pose.pose.orientation.w = 1 # initialize orientation with a valid quaternion
4135

42-
rospy.Timer(rospy.Duration(0.1), self.timer_cb)
43-
4436
rospy.loginfo("Emulation for laser odometry running")
4537

4638
def odometry_callback(self, msg):
4739
self._odom = msg
4840
self._odom.header.frame_id = self._odom_frame
4941
self._odom_publisher.publish(self._odom)
42+
self.publish_tf()
5043

51-
def timer_cb(self, event):
52-
# move robot (calculate new pose)
53-
dt = rospy.Time.now() - self._timestamp_last_update
54-
self._timestamp_last_update = rospy.Time.now()
55-
time_since_last_odom = rospy.Time.now() - self._timestamp_last_odom
56-
57-
#print "dt =", dt.to_sec(), ". duration since last twist =", time_since_last_odom.to_sec()
58-
# we assume we're not moving any more if there is no new twist after 0.1 sec
59-
if time_since_last_odom < rospy.Duration(0.1):
60-
new_pose = copy.deepcopy(self._odom.pose.pose)
61-
yaw = tf.transformations.euler_from_quaternion([self._odom.pose.pose.orientation.x, self._odom.pose.pose.orientation.y, self._odom.pose.pose.orientation.z, self._odom.pose.pose.orientation.w])[2] + self._odom.twist.twist.angular.z * dt.to_sec()
62-
quat = tf.transformations.quaternion_from_euler(0, 0, yaw)
63-
new_pose.orientation.x = quat[0]
64-
new_pose.orientation.y = quat[1]
65-
new_pose.orientation.z = quat[2]
66-
new_pose.orientation.w = quat[3]
67-
new_pose.position.x += self._odom.twist.twist.linear.x * dt.to_sec() * math.cos(yaw) - self._odom.twist.twist.linear.y * dt.to_sec() * math.sin(yaw)
68-
new_pose.position.y += self._odom.twist.twist.linear.x * dt.to_sec() * math.sin(yaw) + self._odom.twist.twist.linear.y * dt.to_sec() * math.cos(yaw)
69-
self._odom.pose.pose = new_pose
70-
71-
# we're moving, so we set a non-zero twist
72-
self._odom.twist.twist.linear.x = self._odom.twist.twist.linear.x
73-
self._odom.twist.twist.linear.y = self._odom.twist.twist.linear.y
74-
self._odom.twist.twist.angular.z = self._odom.twist.twist.angular.z
75-
else:
76-
# reset twist as we're not moving anymore
77-
self._odom.twist.twist = Twist()
78-
44+
def publish_tf(self):
7945
# publish tf
8046
# pub base_footprint --> odom_frame
8147
t_odom = TransformStamped()
82-
t_odom.header.stamp = rospy.Time.now()
48+
t_odom.header.stamp = self._odom.header.stamp
8349
t_odom.header.frame_id = self._odom_frame
8450
t_odom.child_frame_id = "base_footprint"
8551
t_odom.transform.translation = self._odom.pose.pose.position

0 commit comments

Comments
 (0)