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 # Copyright 2018 RT Corporation
5 #
6 # Licensed under the Apache License, Version 2.0 (the "License");
7 # you may not use this file except in compliance with the License.
8 # You may obtain a copy of the License at
9 #
10 # http://www.apache.org/licenses/LICENSE-2.0
11 #
12 # Unless required by applicable law or agreed to in writing, software
13 # distributed under the License is distributed on an "AS IS" BASIS,
14 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 # See the License for the specific language governing permissions and
16 # limitations under the License.
17 
18 import rospy
19 import moveit_commander
20 import geometry_msgs.msg
21 import rosnode
22 import actionlib
23 from tf.transformations import quaternion_from_euler
24 from control_msgs.msg import (GripperCommandAction, GripperCommandGoal)
25 
26 
27 def main():
28  rospy.init_node("sciurus17_pick_and_place_controller")
29  robot = moveit_commander.RobotCommander()
30  arm = moveit_commander.MoveGroupCommander("r_arm_waist_group")
31  arm.set_max_velocity_scaling_factor(0.1)
32  gripper = actionlib.SimpleActionClient("/sciurus17/controller1/right_hand_controller/gripper_cmd", GripperCommandAction)
33  gripper.wait_for_server()
34  gripper_goal = GripperCommandGoal()
35  gripper_goal.command.max_effort = 2.0
36 
37  rospy.sleep(1.0)
38 
39  print("Group names:")
40  print(robot.get_group_names())
41 
42  print("Current state:")
43  print(robot.get_current_state())
44 
45  # アーム初期ポーズを表示
46  # Displays the arm's initial pose
47  arm_initial_pose = arm.get_current_pose().pose
48  print("Arm initial pose:")
49  print(arm_initial_pose)
50 
51  # 何かを掴んでいた時のためにハンドを開く
52  # Opens the hand in case it's holding on to something
53  gripper_goal.command.position = 0.9
54  gripper.send_goal(gripper_goal)
55  gripper.wait_for_result(rospy.Duration(1.0))
56 
57  # SRDFに定義されている"home"の姿勢にする
58  # Moves to the pose declared as "home" in the SRDF
59  arm.set_named_target("r_arm_waist_init_pose")
60  arm.go()
61  gripper_goal.command.position = 0.0
62  gripper.send_goal(gripper_goal)
63  gripper.wait_for_result(rospy.Duration(1.0))
64 
65  # 掴む準備をする
66  # Prepares for grasping
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.3
71  # When grasping from above
72  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
73  target_pose.orientation.x = q[0]
74  target_pose.orientation.y = q[1]
75  target_pose.orientation.z = q[2]
76  target_pose.orientation.w = q[3]
77  arm.set_pose_target(target_pose) # 目標ポーズ設定
78  arm.go() # 実行
79 
80  # ハンドを開く
81  # Opens the hand
82  gripper_goal.command.position = 0.7
83  gripper.send_goal(gripper_goal)
84  gripper.wait_for_result(rospy.Duration(1.0))
85 
86  # 掴みに行く
87  # Grasp!
88  target_pose = geometry_msgs.msg.Pose()
89  target_pose.position.x = 0.25
90  target_pose.position.y = 0.0
91  target_pose.position.z = 0.13
92  # When grasping from above
93  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
94  target_pose.orientation.x = q[0]
95  target_pose.orientation.y = q[1]
96  target_pose.orientation.z = q[2]
97  target_pose.orientation.w = q[3]
98  arm.set_pose_target(target_pose) # 目標ポーズ設定
99  arm.go() # 実行
100 
101  # ハンドを閉じる
102  # Closes the hand
103  gripper_goal.command.position = 0.4
104  gripper.send_goal(gripper_goal)
105  gripper.wait_for_result(rospy.Duration(1.0))
106 
107  # 持ち上げる
108  # Pick up
109  target_pose = geometry_msgs.msg.Pose()
110  target_pose.position.x = 0.25
111  target_pose.position.y = 0.0
112  target_pose.position.z = 0.3
113  # When grasping from above
114  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
115  target_pose.orientation.x = q[0]
116  target_pose.orientation.y = q[1]
117  target_pose.orientation.z = q[2]
118  target_pose.orientation.w = q[3]
119  arm.set_pose_target(target_pose) # 目標ポーズ設定
120  arm.go() # 実行
121 
122  # 移動する
123  # Moves to a different positoin
124  target_pose = geometry_msgs.msg.Pose()
125  target_pose.position.x = 0.4
126  target_pose.position.y = 0.0
127  target_pose.position.z = 0.3
128  # When grasping from above
129  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
130  target_pose.orientation.x = q[0]
131  target_pose.orientation.y = q[1]
132  target_pose.orientation.z = q[2]
133  target_pose.orientation.w = q[3]
134  arm.set_pose_target(target_pose) # 目標ポーズ設定
135  arm.go() # 実行
136 
137  # 下ろす
138  # Lowers the arm
139  target_pose = geometry_msgs.msg.Pose()
140  target_pose.position.x = 0.4
141  target_pose.position.y = 0.0
142  target_pose.position.z = 0.13
143  # When grasping from above
144  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
145  target_pose.orientation.x = q[0]
146  target_pose.orientation.y = q[1]
147  target_pose.orientation.z = q[2]
148  target_pose.orientation.w = q[3]
149  arm.set_pose_target(target_pose) # 目標ポーズ設定
150  arm.go() # 実行
151 
152  # ハンドを開く
153  # Opens the hand
154  gripper_goal.command.position = 0.7
155  gripper.send_goal(gripper_goal)
156  gripper.wait_for_result(rospy.Duration(1.0))
157 
158  # 少しだけハンドを持ち上げる
159  # Raises the hand a little
160  target_pose = geometry_msgs.msg.Pose()
161  target_pose.position.x = 0.4
162  target_pose.position.y = 0.0
163  target_pose.position.z = 0.2
164  # When grasping from above
165  q = quaternion_from_euler(3.14/2.0, 0.0, 0.0) # 上方から掴みに行く場合
166  target_pose.orientation.x = q[0]
167  target_pose.orientation.y = q[1]
168  target_pose.orientation.z = q[2]
169  target_pose.orientation.w = q[3]
170  arm.set_pose_target(target_pose) # 目標ポーズ設定
171  arm.go() # 実行
172 
173  # SRDFに定義されている"home"の姿勢にする
174  # Moves to the pose declared as "home" in the SRDF
175  arm.set_named_target("r_arm_waist_init_pose")
176  arm.go()
177 
178  print("done")
179 
180 
181 if __name__ == '__main__':
182 
183  try:
184  if not rospy.is_shutdown():
185  main()
186  except rospy.ROSInterruptException:
187  pass
pick_and_place_right_arm_demo.main
def main()
Definition: pick_and_place_right_arm_demo.py:27
actionlib::SimpleActionClient


sciurus17_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Fri Aug 2 2024 08:37:20