pick_and_place_right_arm_demo.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import rospy
5 import moveit_commander
6 import geometry_msgs.msg
7 import rosnode
8 import actionlib
9 from tf.transformations import quaternion_from_euler
10 from control_msgs.msg import (GripperCommandAction, GripperCommandGoal)
11 
12 
13 def main():
14  rospy.init_node("sciurus17_pick_and_place_controller")
15  robot = moveit_commander.RobotCommander()
16  arm = moveit_commander.MoveGroupCommander("r_arm_waist_group")
17  arm.set_max_velocity_scaling_factor(0.1)
18  gripper = actionlib.SimpleActionClient("/sciurus17/controller1/right_hand_controller/gripper_cmd", GripperCommandAction)
19  gripper.wait_for_server()
20  gripper_goal = GripperCommandGoal()
21  gripper_goal.command.max_effort = 2.0
22 
23  rospy.sleep(1.0)
24 
25  print("Group names:")
26  print(robot.get_group_names())
27 
28  print("Current state:")
29  print(robot.get_current_state())
30 
31  # アーム初期ポーズを表示
32  arm_initial_pose = arm.get_current_pose().pose
33  print("Arm initial pose:")
34  print(arm_initial_pose)
35 
36  # 何かを掴んでいた時のためにハンドを開く
37  gripper_goal.command.position = 0.9
38  gripper.send_goal(gripper_goal)
39  gripper.wait_for_result(rospy.Duration(1.0))
40 
41  # SRDFに定義されている"home"の姿勢にする
42  arm.set_named_target("r_arm_waist_init_pose")
43  arm.go()
44  gripper_goal.command.position = 0.0
45  gripper.send_goal(gripper_goal)
46  gripper.wait_for_result(rospy.Duration(1.0))
47 
48  # 掴む準備をする
49  target_pose = geometry_msgs.msg.Pose()
50  target_pose.position.x = 0.25
51  target_pose.position.y = 0.0
52  target_pose.position.z = 0.3
53  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
54  target_pose.orientation.x = q[0]
55  target_pose.orientation.y = q[1]
56  target_pose.orientation.z = q[2]
57  target_pose.orientation.w = q[3]
58  arm.set_pose_target(target_pose) # 目標ポーズ設定
59  arm.go() # 実行
60 
61  # ハンドを開く
62  gripper_goal.command.position = 0.7
63  gripper.send_goal(gripper_goal)
64  gripper.wait_for_result(rospy.Duration(1.0))
65 
66  # 掴みに行く
67  target_pose = geometry_msgs.msg.Pose()
68  target_pose.position.x = 0.25
69  target_pose.position.y = 0.0
70  target_pose.position.z = 0.13
71  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
72  target_pose.orientation.x = q[0]
73  target_pose.orientation.y = q[1]
74  target_pose.orientation.z = q[2]
75  target_pose.orientation.w = q[3]
76  arm.set_pose_target(target_pose) # 目標ポーズ設定
77  arm.go() # 実行
78 
79  # ハンドを閉じる
80  gripper_goal.command.position = 0.4
81  gripper.send_goal(gripper_goal)
82  gripper.wait_for_result(rospy.Duration(1.0))
83 
84  # 持ち上げる
85  target_pose = geometry_msgs.msg.Pose()
86  target_pose.position.x = 0.25
87  target_pose.position.y = 0.0
88  target_pose.position.z = 0.3
89  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
90  target_pose.orientation.x = q[0]
91  target_pose.orientation.y = q[1]
92  target_pose.orientation.z = q[2]
93  target_pose.orientation.w = q[3]
94  arm.set_pose_target(target_pose) # 目標ポーズ設定
95  arm.go() # 実行
96 
97  # 移動する
98  target_pose = geometry_msgs.msg.Pose()
99  target_pose.position.x = 0.4
100  target_pose.position.y = 0.0
101  target_pose.position.z = 0.3
102  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
103  target_pose.orientation.x = q[0]
104  target_pose.orientation.y = q[1]
105  target_pose.orientation.z = q[2]
106  target_pose.orientation.w = q[3]
107  arm.set_pose_target(target_pose) # 目標ポーズ設定
108  arm.go() # 実行
109 
110  # 下ろす
111  target_pose = geometry_msgs.msg.Pose()
112  target_pose.position.x = 0.4
113  target_pose.position.y = 0.0
114  target_pose.position.z = 0.13
115  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
116  target_pose.orientation.x = q[0]
117  target_pose.orientation.y = q[1]
118  target_pose.orientation.z = q[2]
119  target_pose.orientation.w = q[3]
120  arm.set_pose_target(target_pose) # 目標ポーズ設定
121  arm.go() # 実行
122 
123  # ハンドを開く
124  gripper_goal.command.position = 0.7
125  gripper.send_goal(gripper_goal)
126  gripper.wait_for_result(rospy.Duration(1.0))
127 
128  # 少しだけハンドを持ち上げる
129  target_pose = geometry_msgs.msg.Pose()
130  target_pose.position.x = 0.4
131  target_pose.position.y = 0.0
132  target_pose.position.z = 0.2
133  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
134  target_pose.orientation.x = q[0]
135  target_pose.orientation.y = q[1]
136  target_pose.orientation.z = q[2]
137  target_pose.orientation.w = q[3]
138  arm.set_pose_target(target_pose) # 目標ポーズ設定
139  arm.go() # 実行
140 
141  # SRDFに定義されている"home"の姿勢にする
142  arm.set_named_target("r_arm_waist_init_pose")
143  arm.go()
144 
145  print("done")
146 
147 
148 if __name__ == '__main__':
149 
150  try:
151  if not rospy.is_shutdown():
152  main()
153  except rospy.ROSInterruptException:
154  pass


sciurus17_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Sun Oct 2 2022 02:21:39