|
31 | 31 | # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
32 | 32 | # POSSIBILITY OF SUCH DAMAGE.
|
33 | 33 |
|
34 |
| -import roslib; roslib.load_manifest( 'rviz_plugin_covariance' ) |
35 | 34 | from geometry_msgs.msg import PoseWithCovarianceStamped, PoseStamped
|
36 | 35 | import rospy
|
37 | 36 | from math import cos, sin, pi
|
38 |
| -import tf |
39 |
| -import tf_conversions |
| 37 | +import tf2_ros |
| 38 | +import tf_conversions as tf |
| 39 | +from geometry_msgs.msg import TransformStamped, Vector3 |
40 | 40 |
|
41 | 41 | publisher_cov = rospy.Publisher( 'pose_with_cov', PoseWithCovarianceStamped, queue_size=5 )
|
42 | 42 | publisher_pose = rospy.Publisher( 'pose', PoseStamped, queue_size=5 )
|
43 | 43 |
|
44 | 44 | rospy.init_node( 'test_covariance' )
|
45 | 45 |
|
46 |
| -br = tf.TransformBroadcaster() |
| 46 | +br = tf2_ros.TransformBroadcaster() |
47 | 47 | rate = rospy.Rate(100)
|
48 | 48 | # radius = 1
|
49 | 49 | angle = 0
|
50 | 50 | # r = 0
|
51 | 51 | # p = 0
|
52 | 52 | # y = 0
|
53 | 53 |
|
54 |
| -linear_deviation = 0.5; |
55 |
| - |
| 54 | +linear_deviation = 0.5 |
56 | 55 |
|
57 | 56 | while not rospy.is_shutdown():
|
58 | 57 | stamp = rospy.Time.now()
|
|
91 | 90 | publisher_cov.publish( pose_with_cov )
|
92 | 91 | publisher_pose.publish( pose )
|
93 | 92 |
|
94 |
| - # br.sendTransform((radius * cos(angle), radius * sin(angle), 0), |
95 |
| - # tf.transformations.quaternion_from_euler(r, p, y), |
96 |
| - # rospy.Time.now(), |
97 |
| - # "base_link", |
98 |
| - # "map") |
99 |
| - pos, ori = pose_with_cov.pose.pose.position, pose_with_cov.pose.pose.orientation |
100 |
| - br.sendTransform((pos.x, pos.y, pos.z), |
101 |
| - (ori.x, ori.y, ori.z, ori.w), |
102 |
| - stamp, |
103 |
| - "pose", |
104 |
| - "base_link") |
| 93 | + t = TransformStamped() |
| 94 | + t.header.frame_id = 'base_link' |
| 95 | + t.header.stamp = stamp |
| 96 | + t.child_frame_id = 'pose' |
| 97 | + |
| 98 | + if 0: |
| 99 | + t.transform.translation = Vector3(radius * cos(angle), radius * sin(angle), 0) |
| 100 | + t.transform.rotation = tf.transformations.quaternion_from_euler(r, p, y) |
| 101 | + br.sendTransform(t) |
| 102 | + else: |
| 103 | + t.transform.translation = pose_with_cov.pose.pose.position |
| 104 | + t.transform.rotation = pose_with_cov.pose.pose.orientation |
| 105 | + br.sendTransform(t) |
105 | 106 |
|
106 | 107 | angle += .0005
|
107 | 108 | # r = angle
|
108 | 109 | # p = angle
|
109 | 110 | # y = angle
|
110 | 111 | rate.sleep()
|
111 |
| - |
0 commit comments