22 from gazebo_msgs.msg
import ContactsState
23 from std_msgs.msg
import Float64
30 if (ContactsState.states != []):
31 rospy.loginfo(
"button pressed")
32 rand = (random.randint(0,1))
38 rospy.logdebug(
"button not pressed")
40 rospy.loginfo(
"Door Opened")
44 rospy.init_node(
'listener', anonymous=
True)
45 rospy.Subscriber(
"/elevator_button1_bumper", ContactsState, callback, queue_size=1)
51 topic_name =
'/world/elevator_%s_joint_position_controller/command' %side
52 pub = rospy.Publisher(topic_name,Float64,queue_size=10)
57 rospy.loginfo(
"%s door is opening" %side)
61 except rospy.exceptions.ROSInterruptException:
65 rospy.loginfo(
"%s door is closing" %side)
70 except rospy.exceptions.ROSInterruptException:
75 if __name__ ==
'__main__':
def callback(ContactsState)