ed_rviz_plugins
send_test_msgs.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import roslib; roslib.load_manifest( 'rviz_plugin_tutorials' )
4 from sensor_msgs.msg import Imu
5 import rospy
6 from math import cos, sin
7 import tf
8 
9 topic = 'test_imu'
10 publisher = rospy.Publisher( topic, Imu )
11 
12 rospy.init_node( 'test_imu' )
13 
14 br = tf.TransformBroadcaster()
15 rate = rospy.Rate(10)
16 radius = 5
17 angle = 0
18 
19 dist = 3
20 while not rospy.is_shutdown():
21 
22  imu = Imu()
23  imu.header.frame_id = "/base_link"
24  imu.header.stamp = rospy.Time.now()
25 
26  imu.linear_acceleration.x = sin( 10 * angle )
27  imu.linear_acceleration.y = sin( 20 * angle )
28  imu.linear_acceleration.z = sin( 40 * angle )
29 
30  publisher.publish( imu )
31 
32  br.sendTransform((radius * cos(angle), radius * sin(angle), 0),
33  tf.transformations.quaternion_from_euler(0, 0, angle),
34  rospy.Time.now(),
35  "base_link",
36  "map")
37  angle += .01
38  rate.sleep()
39