3 from sensor_msgs.msg
import JointState
7 rospy.init_node(
'fake_mir_joint_publisher')
8 prefix = rospy.get_param(
'~prefix',
'')
9 pub = rospy.Publisher(
'joint_states', JointState, queue_size=10)
11 while not rospy.is_shutdown():
13 js.header.stamp = rospy.Time.now()
15 prefix +
'left_wheel_joint',
16 prefix +
'right_wheel_joint',
17 prefix +
'fl_caster_rotation_joint',
18 prefix +
'fl_caster_wheel_joint',
19 prefix +
'fr_caster_rotation_joint',
20 prefix +
'fr_caster_wheel_joint',
21 prefix +
'bl_caster_rotation_joint',
22 prefix +
'bl_caster_wheel_joint',
23 prefix +
'br_caster_rotation_joint',
24 prefix +
'br_caster_wheel_joint',
26 js.position = [0.0
for _
in js.name]
27 js.velocity = [0.0
for _
in js.name]
28 js.effort = [0.0
for _
in js.name]
33 if __name__ ==
'__main__':
36 except rospy.ROSInterruptException:
def fake_mir_joint_publisher()