contact_state_sample.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 from hrpsys_ros_bridge.msg import ContactState, ContactStateStamped, ContactStatesStamped
5 from random import random
6 if __name__ == "__main__":
7  rospy.init_node("contact_state_sample")
8  pub = rospy.Publisher("~output", ContactStatesStamped)
9  link_names = rospy.get_param("~links", ["r_shoulder_pan_link"])
10  rate = rospy.Rate(1)
11  while not rospy.is_shutdown():
12  states = ContactStatesStamped()
13  states.header.stamp = rospy.Time.now()
14  for link_name in link_names:
15  state = ContactStateStamped()
16  state.header.frame_id = link_name
17  state.header.stamp = rospy.Time.now()
18  if random() < 0.5:
19  state.state.state = ContactState.ON
20  else:
21  state.state.state = ContactState.OFF
22  states.states.append(state)
23  pub.publish(states)
24  rate.sleep()


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Fri Dec 13 2024 03:49:56