35 from threading
import Thread
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
51 self.
process = subprocess.Popen([
"roslaunch",
"fetch_moveit_config",
"move_group.launch",
"--wait"])
52 _, _ = self.
process.communicate()
55 self.
process.send_signal(subprocess.signal.SIGINT)
60 output = subprocess.check_output([
"rosnode",
"info",
"move_group"], stderr=subprocess.STDOUT)
61 except subprocess.CalledProcessError
as e:
63 if output.find(
"unknown node") >= 0:
65 if output.find(
"Communication with node") >= 0:
79 rospy.loginfo(
"starting moveit")
82 rospy.loginfo(
"moveit already started")
84 rospy.loginfo(
"Waiting for MoveIt...")
85 self.
client = MoveGroupInterface(
"arm_with_torso",
"base_link")
86 rospy.loginfo(
"...connected")
90 scene = PlanningSceneInterface(
"base_link")
92 keepout_pose.position.z = 0.375
93 keepout_pose.orientation.w = 1.0
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')
100 'keepout', keepout_pose, os.path.join(mesh_dir,
'keepout.stl'))
102 'ground', ground_pose, os.path.join(mesh_dir,
'ground.stl'))
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,
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")
122 rospy.signal_shutdown(
"done")
128 self.
client.get_move_action().cancel_goal()
132 rospy.signal_shutdown(
"failed")
139 self.
deadman = rospy.get_param(
"~deadman_button", 10)
150 if msg.buttons[self.
deadman] <= 0:
152 rospy.loginfo(
"Stopping tuck thread")
163 rospy.loginfo(
"Starting tuck thread")
168 rospy.logwarn(
"tuck_button is out of range")
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()
175 rospy.init_node(
"tuck_arm")
176 rospy.loginfo(
"New tuck script running")
182 rospy.loginfo(
"Tucking the arm")
def joy_callback(self, msg)