3 import roslib; roslib.load_manifest(
'rviz_plugin_tutorials' )
4 from sensor_msgs.msg
import Imu
6 from math
import cos, sin
10 publisher = rospy.Publisher( topic, Imu )
12 rospy.init_node(
'test_imu' )
14 br = tf.TransformBroadcaster()
20 while not rospy.is_shutdown():
23 imu.header.frame_id =
"/base_link"
24 imu.header.stamp = rospy.Time.now()
26 imu.linear_acceleration.x = sin( 10 * angle )
27 imu.linear_acceleration.y = sin( 20 * angle )
28 imu.linear_acceleration.z = sin( 40 * angle )
30 publisher.publish( imu )
32 br.sendTransform((radius * cos(angle), radius * sin(angle), 0),
33 tf.transformations.quaternion_from_euler(0, 0, angle),