full_arm_holder.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2009, Willow Garage, Inc.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the Willow Garage nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 ##\author Kevin Watts
36 ##\brief Raises torso and moves arms of PR2 for counterbalance check
37 
38 PKG='pr2_counterbalance_check'
39 import rospy, sys, time
40 import subprocess
41 from optparse import OptionParser
42 from std_msgs.msg import Bool, Float64
43 
44 import actionlib
45 from pr2_controllers_msgs.msg import *
46 
47 
48 class SendMessageOnSubscribe(rospy.SubscribeListener):
49  def __init__(self, msg):
50  self.msg = msg
51  print "Waiting for subscriber..."
52 
53  def peer_subscribe(self, topic_name, topic_publish, peer_publish):
54  peer_publish(self.msg)
55  time.sleep(0.1)
56 
57 
58 def set_controller(controller, command):
59  pub = rospy.Publisher(controller + '/command', Float64,
60  SendMessageOnSubscribe(Float64(command)))
61 
62 def hold_arm(side, pan_angle):
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))
70 
72  client = actionlib.SimpleActionClient('torso_controller/position_joint_action', SingleJointPositionAction)
73 
74  goal = SingleJointPositionGoal()
75  goal.position = 0.25
76  goal.min_duration = rospy.Duration(2.0)
77  goal.max_velocity = 1.0
78 
79  rospy.loginfo("Moving torso up")
80  client.send_goal(goal)
81  client.wait_for_result(rospy.Duration.from_sec(5))
82 
83 
84 
85 def main():
86  parser = OptionParser()
87  parser.add_option('--wait-for', action="store", dest="wait_for_topic", default=None)
88 
89  options, args = parser.parse_args(rospy.myargv())
90 
91  rospy.init_node('arm_test_holder')
92  pub_held = rospy.Publisher('arms_held', Bool, latch=True)
93 
94 
95  try:
96  if options.wait_for_topic:
97  global result
98  result = None
99  def wait_for_topic_cb(msg):
100  global result
101  result = msg
102 
103  rospy.Subscriber(options.wait_for_topic, Bool, wait_for_topic_cb)
104  started_waiting = rospy.get_time()
105 
106  # We might not have receieved any time messages yet
107  warned_about_not_hearing_anything = False
108  while not result and not rospy.is_shutdown():
109  time.sleep(0.01)
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)
115  if result:
116  while not result.data and not rospy.is_shutdown():
117  time.sleep(0.01)
118 
119  if not rospy.is_shutdown():
120  rospy.loginfo('Raising torso')
121  move_torso_up()
122 
123  if not rospy.is_shutdown():
124  rospy.loginfo('Holding arms')
125  # Hold both arms in place
126  hold_arm('r', -1.2)
127  hold_arm('l', 1.2)
128  time.sleep(1.5)
129 
130  if not rospy.is_shutdown():
131  pub_held.publish(True)
132 
133  rospy.spin()
134  except KeyboardInterrupt:
135  pass
136  except Exception, e:
137  import traceback
138  traceback.print_exc()
139 
140 if __name__ == '__main__':
141  main()
def peer_subscribe(self, topic_name, topic_publish, peer_publish)
def set_controller(controller, command)
def hold_arm(side, pan_angle)


pr2_counterbalance_check
Author(s): Kevin Watts
autogenerated on Wed Jan 6 2021 03:39:25