4 from sensor_msgs.msg
import JointState
7 rospy.init_node(
'hand_joint_state_publisher', anonymous=
True)
8 pub = rospy.Publisher(
'joint_states', JointState, queue_size=1)
9 joint_list = [
'LHAND_JOINT0',
'LHAND_JOINT1',
'LHAND_JOINT2',
'LHAND_JOINT3',
'RHAND_JOINT0',
'RHAND_JOINT1',
'RHAND_JOINT2',
'RHAND_JOINT3']
10 rospy.loginfo(
"{} publishes fake joint states of {}".format(rospy.get_name(), joint_list))
12 while not rospy.is_shutdown():
13 joint_states = JointState()
14 joint_states.header.stamp = rospy.Time.now()
15 joint_states.name = []
16 joint_states.position = []
17 for joint
in joint_list:
18 joint_states.name.append(joint)
19 joint_states.position.append(0)
20 rospy.logdebug(joint_states)
21 pub.publish(joint_states)
24 if __name__ ==
'__main__':
27 except rospy.ROSInterruptException:
def joint_state_publisher()