crane_x7_pick_and_place_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 from tf.transformations import quaternion_from_euler
23 
24 
25 def main():
26  rospy.init_node("crane_x7_pick_and_place_controller")
27  robot = moveit_commander.RobotCommander()
28  arm = moveit_commander.MoveGroupCommander("arm")
29  arm.set_max_velocity_scaling_factor(0.1)
30  arm.set_max_acceleration_scaling_factor(1.0)
31  gripper = moveit_commander.MoveGroupCommander("gripper")
32 
33  while len([s for s in rosnode.get_node_names() if 'rviz' in s]) == 0:
34  rospy.sleep(1.0)
35  rospy.sleep(1.0)
36 
37  print("Group names:")
38  print(robot.get_group_names())
39 
40  print("Current state:")
41  print(robot.get_current_state())
42 
43  # アーム初期ポーズを表示
44  arm_initial_pose = arm.get_current_pose().pose
45  print("Arm initial pose:")
46  print(arm_initial_pose)
47 
48  # 何かを掴んでいた時のためにハンドを開く
49  gripper.set_joint_value_target([0.9, 0.9])
50  gripper.go()
51 
52  # SRDFに定義されている"home"の姿勢にする
53  arm.set_named_target("home")
54  arm.go()
55  gripper.set_joint_value_target([0.7, 0.7])
56  gripper.go()
57 
58  # 掴む準備をする
59  target_pose = geometry_msgs.msg.Pose()
60  target_pose.position.x = 0.2
61  target_pose.position.y = 0.0
62  target_pose.position.z = 0.3
63  q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0) # 上方から掴みに行く場合
64  target_pose.orientation.x = q[0]
65  target_pose.orientation.y = q[1]
66  target_pose.orientation.z = q[2]
67  target_pose.orientation.w = q[3]
68  arm.set_pose_target(target_pose) # 目標ポーズ設定
69  arm.go() # 実行
70 
71  # ハンドを開く
72  gripper.set_joint_value_target([0.7, 0.7])
73  gripper.go()
74 
75  # 掴みに行く
76  target_pose = geometry_msgs.msg.Pose()
77  target_pose.position.x = 0.2
78  target_pose.position.y = 0.0
79  target_pose.position.z = 0.13
80  q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0) # 上方から掴みに行く場合
81  target_pose.orientation.x = q[0]
82  target_pose.orientation.y = q[1]
83  target_pose.orientation.z = q[2]
84  target_pose.orientation.w = q[3]
85  arm.set_pose_target(target_pose) # 目標ポーズ設定
86  arm.go() # 実行
87 
88  # ハンドを閉じる
89  gripper.set_joint_value_target([0.4, 0.4])
90  gripper.go()
91 
92  # 持ち上げる
93  target_pose = geometry_msgs.msg.Pose()
94  target_pose.position.x = 0.2
95  target_pose.position.y = 0.0
96  target_pose.position.z = 0.3
97  q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0) # 上方から掴みに行く場合
98  target_pose.orientation.x = q[0]
99  target_pose.orientation.y = q[1]
100  target_pose.orientation.z = q[2]
101  target_pose.orientation.w = q[3]
102  arm.set_pose_target(target_pose) # 目標ポーズ設定
103  arm.go() # 実行
104 
105  # 移動する
106  target_pose = geometry_msgs.msg.Pose()
107  target_pose.position.x = 0.2
108  target_pose.position.y = 0.2
109  target_pose.position.z = 0.3
110  q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0) # 上方から掴みに行く場合
111  target_pose.orientation.x = q[0]
112  target_pose.orientation.y = q[1]
113  target_pose.orientation.z = q[2]
114  target_pose.orientation.w = q[3]
115  arm.set_pose_target(target_pose) # 目標ポーズ設定
116  arm.go() # 実行
117 
118  # 下ろす
119  target_pose = geometry_msgs.msg.Pose()
120  target_pose.position.x = 0.2
121  target_pose.position.y = 0.2
122  target_pose.position.z = 0.13
123  q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0) # 上方から掴みに行く場合
124  target_pose.orientation.x = q[0]
125  target_pose.orientation.y = q[1]
126  target_pose.orientation.z = q[2]
127  target_pose.orientation.w = q[3]
128  arm.set_pose_target(target_pose) # 目標ポーズ設定
129  arm.go() # 実行
130 
131  # ハンドを開く
132  gripper.set_joint_value_target([0.7, 0.7])
133  gripper.go()
134 
135  # 少しだけハンドを持ち上げる
136  target_pose = geometry_msgs.msg.Pose()
137  target_pose.position.x = 0.2
138  target_pose.position.y = 0.2
139  target_pose.position.z = 0.2
140  q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0) # 上方から掴みに行く場合
141  target_pose.orientation.x = q[0]
142  target_pose.orientation.y = q[1]
143  target_pose.orientation.z = q[2]
144  target_pose.orientation.w = q[3]
145  arm.set_pose_target(target_pose) # 目標ポーズ設定
146  arm.go() # 実行
147 
148  # SRDFに定義されている"home"の姿勢にする
149  arm.set_named_target("home")
150  arm.go()
151 
152  print("done")
153 
154 
155 if __name__ == '__main__':
156 
157  try:
158  if not rospy.is_shutdown():
159  main()
160  except rospy.ROSInterruptException:
161  pass
crane_x7_pick_and_place_demo.main
def main()
Definition: crane_x7_pick_and_place_demo.py:25


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Oct 2 2023 02:39:27