38 PKG=
'pr2_counterbalance_check' 39 import rospy, sys, time
41 from optparse
import OptionParser
42 from std_msgs.msg
import Bool, Float64
51 print "Waiting for subscriber..." 54 peer_publish(self.
msg)
59 pub = rospy.Publisher(controller +
'/command', Float64,
63 set_controller(
"%s_wrist_roll_position_controller" % side, float(0.0))
64 set_controller(
"%s_wrist_flex_position_controller" % side, float(0.0))
65 set_controller(
"%s_forearm_roll_position_controller" % side, float(0.0))
66 set_controller(
"%s_elbow_flex_position_controller" % side, float(-0.5))
67 set_controller(
"%s_upper_arm_roll_position_controller" % side, float(0.0))
68 set_controller(
"%s_shoulder_lift_position_controller" % side, float(0.0))
69 set_controller(
"%s_shoulder_pan_position_controller" % side, float(pan_angle))
74 goal = SingleJointPositionGoal()
76 goal.min_duration = rospy.Duration(2.0)
77 goal.max_velocity = 1.0
79 rospy.loginfo(
"Moving torso up")
80 client.send_goal(goal)
81 client.wait_for_result(rospy.Duration.from_sec(5))
86 parser = OptionParser()
87 parser.add_option(
'--wait-for', action=
"store", dest=
"wait_for_topic", default=
None)
89 options, args = parser.parse_args(rospy.myargv())
91 rospy.init_node(
'arm_test_holder')
92 pub_held = rospy.Publisher(
'arms_held', Bool, latch=
True)
96 if options.wait_for_topic:
99 def wait_for_topic_cb(msg):
103 rospy.Subscriber(options.wait_for_topic, Bool, wait_for_topic_cb)
104 started_waiting = rospy.get_time()
107 warned_about_not_hearing_anything =
False 108 while not result
and not rospy.is_shutdown():
110 if not warned_about_not_hearing_anything:
111 if rospy.get_time() - started_waiting > 10.0:
112 warned_about_not_hearing_anything =
True 113 rospy.logwarn(
"Full arm holder hasn't heard anything from its \"wait for\" topic (%s)" % \
114 options.wait_for_topic)
116 while not result.data
and not rospy.is_shutdown():
119 if not rospy.is_shutdown():
120 rospy.loginfo(
'Raising torso')
123 if not rospy.is_shutdown():
124 rospy.loginfo(
'Holding arms')
130 if not rospy.is_shutdown():
131 pub_held.publish(
True)
134 except KeyboardInterrupt:
138 traceback.print_exc()
140 if __name__ ==
'__main__':
def peer_subscribe(self, topic_name, topic_publish, peer_publish)
def set_controller(controller, command)
def hold_arm(side, pan_angle)