tuck_arm.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 # Copyright (c) 2015, Fetch Robotics Inc.
4 # All rights reserved.
5 #
6 # Redistribution and use in source and binary forms, with or without
7 # modification, are permitted provided that the following conditions are met:
8 #
9 # * Redistributions of source code must retain the above copyright
10 # notice, this list of conditions and the following disclaimer.
11 # * Redistributions in binary form must reproduce the above copyright
12 # notice, this list of conditions and the following disclaimer in the
13 # documentation and/or other materials provided with the distribution.
14 # * Neither the name of the Fetch Robotics Inc. nor the names of its
15 # contributors may be used to endorse or promote products derived from
16 # this software without specific prior written permission.
17 #
18 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 # IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
21 # ARE DISCLAIMED. IN NO EVENT SHALL FETCH ROBOTICS INC. BE LIABLE FOR ANY
22 # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
23 # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
25 # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
26 # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
27 # THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 
29 # Author: Michael Ferguson
30 
31 import argparse
32 import os
33 import subprocess
34 import sys
35 from threading import Thread
36 
37 import rospkg
38 import rospy
39 from sensor_msgs.msg import Joy
40 from geometry_msgs.msg import Pose
41 from moveit_python import MoveGroupInterface, PlanningSceneInterface
42 from moveit_msgs.msg import MoveItErrorCodes, PlanningScene
43 
44 class MoveItThread(Thread):
45 
46  def __init__(self):
47  Thread.__init__(self)
48  self.start()
49 
50  def run(self):
51  self.process = subprocess.Popen(["roslaunch", "fetch_moveit_config", "move_group.launch", "--wait"])
52  _, _ = self.process.communicate()
53 
54  def stop(self):
55  self.process.send_signal(subprocess.signal.SIGINT)
56  self.process.wait()
57 
59  try:
60  output = subprocess.check_output(["rosnode", "info", "move_group"], stderr=subprocess.STDOUT)
61  except subprocess.CalledProcessError as e:
62  output = e.output
63  if output.find("unknown node") >= 0:
64  return False
65  if output.find("Communication with node") >= 0:
66  return False
67  return True
68 
69 class TuckThread(Thread):
70 
71  def __init__(self):
72  Thread.__init__(self)
73  self.client = None
74  self.start()
75 
76  def run(self):
77  move_thread = None
78  if not is_moveit_running():
79  rospy.loginfo("starting moveit")
80  move_thread = MoveItThread()
81  else:
82  rospy.loginfo("moveit already started")
83 
84  rospy.loginfo("Waiting for MoveIt...")
85  self.client = MoveGroupInterface("arm_with_torso", "base_link")
86  rospy.loginfo("...connected")
87 
88  # Padding does not work (especially for self collisions)
89  # So we are adding a box above the base of the robot
90  scene = PlanningSceneInterface("base_link")
91  keepout_pose = Pose()
92  keepout_pose.position.z = 0.375
93  keepout_pose.orientation.w = 1.0
94  ground_pose = Pose()
95  ground_pose.position.z = -0.03
96  ground_pose.orientation.w = 1.0
97  rospack = rospkg.RosPack()
98  mesh_dir = os.path.join(rospack.get_path('fetch_teleop'), 'mesh')
99  scene.addMesh(
100  'keepout', keepout_pose, os.path.join(mesh_dir, 'keepout.stl'))
101  scene.addMesh(
102  'ground', ground_pose, os.path.join(mesh_dir, 'ground.stl'))
103 
104  joints = ["torso_lift_joint", "shoulder_pan_joint", "shoulder_lift_joint", "upperarm_roll_joint",
105  "elbow_flex_joint", "forearm_roll_joint", "wrist_flex_joint", "wrist_roll_joint"]
106  pose = [0.05, 1.32, 1.40, -0.2, 1.72, 0.0, 1.66, 0.0]
107  while not rospy.is_shutdown():
108  result = self.client.moveToJointPosition(joints,
109  pose,
110  0.0,
111  max_velocity_scaling_factor=0.5)
112  if result and result.error_code.val == MoveItErrorCodes.SUCCESS:
113  scene.removeCollisionObject("keepout")
114  scene.removeCollisionObject("ground")
115  if move_thread:
116  move_thread.stop()
117 
118  # On success quit
119  # Stopping the MoveIt thread works, however, the action client
120  # does not get shut down, and future tucks will not work.
121  # As a work-around, we die and roslaunch will respawn us.
122  rospy.signal_shutdown("done")
123  sys.exit(0)
124  return
125 
126  def stop(self):
127  if self.client:
128  self.client.get_move_action().cancel_goal()
129  # Stopping the MoveIt thread works, however, the action client
130  # does not get shut down, and future tucks will not work.
131  # As a work-around, we die and roslaunch will respawn us.
132  rospy.signal_shutdown("failed")
133  sys.exit(0)
134 
136 
137  def __init__(self):
138  self.tuck_button = rospy.get_param("~tuck_button", 6) # default button is the down button
139  self.deadman = rospy.get_param("~deadman_button", 10)
140  self.tucking = False
141 
142  self.pressed = False
143  self.pressed_last = None
144 
145  self.joy_sub = rospy.Subscriber("joy", Joy, self.joy_callback)
146 
147  def joy_callback(self, msg):
148  if self.tucking:
149  # Only run once
150  if msg.buttons[self.deadman] <= 0:
151  # Deadman has been released, don't tuck
152  rospy.loginfo("Stopping tuck thread")
153  self.tuck_thread.stop()
154  return
155  try:
156  if msg.buttons[self.tuck_button] > 0 and msg.buttons[self.deadman] > 0:
157  if not self.pressed:
158  self.pressed_last = rospy.Time.now()
159  self.pressed = True
160  elif self.pressed_last and rospy.Time.now() > self.pressed_last + rospy.Duration(1.0):
161  # Tuck the arm
162  self.tucking = True
163  rospy.loginfo("Starting tuck thread")
165  else:
166  self.pressed = False
167  except KeyError:
168  rospy.logwarn("tuck_button is out of range")
169 
170 if __name__ == "__main__":
171  parser = argparse.ArgumentParser(description="Tuck the arm, either immediately or as a joystck-controlled server.")
172  parser.add_argument("--joystick", action="store_true", help="Run as server that tucks on command from joystick.")
173  args, unknown = parser.parse_known_args()
174 
175  rospy.init_node("tuck_arm")
176  rospy.loginfo("New tuck script running")
177 
178  if args.joystick:
180  rospy.spin()
181  else:
182  rospy.loginfo("Tucking the arm")
183  TuckThread()
def __init__(self)
Definition: tuck_arm.py:71
def joy_callback(self, msg)
Definition: tuck_arm.py:147
def run(self)
Definition: tuck_arm.py:76
def is_moveit_running()
Definition: tuck_arm.py:58
def stop(self)
Definition: tuck_arm.py:126
def __init__(self)
Definition: tuck_arm.py:46


fetch_teleop
Author(s): Michael Ferguson
autogenerated on Mon Feb 28 2022 22:24:06