-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathstatic_tf_cam_publisher.py
executable file
·54 lines (41 loc) · 1.79 KB
/
static_tf_cam_publisher.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
#!/usr/bin/env python
import rospy
import tf2_ros
import geometry_msgs.msg
def talker():
rospy.init_node('static_tf_cam_publisher')
try:
br = tf2_ros.StaticTransformBroadcaster()
left_cam_transform = geometry_msgs.msg.TransformStamped()
left_cam_transform.header.stamp = rospy.Time.now()
left_cam_transform.header.frame_id = "base_link_gt"
left_cam_transform.child_frame_id = "left_cam"
left_cam_transform.transform.translation.x = -0.05
left_cam_transform.transform.translation.y = 0.0
left_cam_transform.transform.translation.z = 0.0
left_cam_transform.transform.rotation.x = 0.0
left_cam_transform.transform.rotation.y = 0.0
left_cam_transform.transform.rotation.z = 0.0
left_cam_transform.transform.rotation.w = 1.0
right_cam_transform = geometry_msgs.msg.TransformStamped()
right_cam_transform.header.stamp = rospy.Time.now()
right_cam_transform.header.frame_id = "base_link_gt"
right_cam_transform.child_frame_id = "right_cam"
right_cam_transform.transform.translation.x = 0.05
right_cam_transform.transform.translation.y = 0.0
right_cam_transform.transform.translation.z = 0.0
right_cam_transform.transform.rotation.x = 0.0
right_cam_transform.transform.rotation.y = 0.0
right_cam_transform.transform.rotation.z = 0.0
right_cam_transform.transform.rotation.w = 1.0
br.sendTransform([right_cam_transform, left_cam_transform])
rospy.spin()
print("sent")
except (tf2_ros.LookupException, tf2_ros.ConnectivityException,
tf2_ros.ExtrapolationException):
print('oop')
if __name__ == '__main__':
try:
talker()
except rospy.ROSInterruptException:
pass