pick_and_place_in_gazebo_example.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Copyright 2019 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 actionlib
21 import math
22 import random
23 from geometry_msgs.msg import Point, Pose
24 from gazebo_msgs.msg import ModelStates
25 from control_msgs.msg import GripperCommandAction, GripperCommandGoal
26 from tf.transformations import quaternion_from_euler, euler_from_quaternion
27 
28 gazebo_model_states = ModelStates()
29 
30 def callback(msg):
31  global gazebo_model_states
32  gazebo_model_states = msg
33 
34 
35 def yaw_of(object_orientation):
36  # クォータニオンをオイラー角に変換しyaw角度を返す
37  euler = euler_from_quaternion(
38  (object_orientation.x, object_orientation.y,
39  object_orientation.z, object_orientation.w))
40 
41  return euler[2]
42 
43 
44 def main():
45  global gazebo_model_states
46 
47  OBJECT_NAME = "wood_cube_5cm" # 掴むオブジェクトの名前
48  GRIPPER_OPEN = 1.2 # 掴む時のハンド開閉角度
49  GRIPPER_CLOSE = 0.42 # 設置時のハンド開閉角度
50  APPROACH_Z = 0.15 # 接近時のハンドの高さ
51  LEAVE_Z = 0.20 # 離れる時のハンドの高さ
52  PICK_Z = 0.12 # 掴む時のハンドの高さ
53  PLACE_POSITIONS = [ # オブジェクトの設置位置 (ランダムに設置する)
54  Point(0.4, 0.0, 0.0),
55  Point(0.0, 0.3, 0.0),
56  Point(0.0, -0.3, 0.0),
57  Point(0.2, 0.2, 0.0),
58  Point(0.2, -0.2, 0.0)]
59 
60  sub_model_states = rospy.Subscriber("gazebo/model_states", ModelStates, callback, queue_size=1)
61 
62  arm = moveit_commander.MoveGroupCommander("arm")
63  arm.set_max_velocity_scaling_factor(0.4)
64  arm.set_max_acceleration_scaling_factor(1.0)
65  gripper = actionlib.SimpleActionClient("crane_x7/gripper_controller/gripper_cmd", GripperCommandAction)
66  gripper.wait_for_server()
67  gripper_goal = GripperCommandGoal()
68  gripper_goal.command.max_effort = 4.0
69 
70  rospy.sleep(1.0)
71 
72  while True:
73  # 何かを掴んでいた時のためにハンドを開く
74  gripper_goal.command.position = GRIPPER_OPEN
75  gripper.send_goal(gripper_goal)
76  gripper.wait_for_result(rospy.Duration(1.0))
77 
78  # SRDFに定義されている"home"の姿勢にする
79  arm.set_named_target("home")
80  arm.go()
81  rospy.sleep(1.0)
82 
83  # 一定時間待機する
84  # この間に、ユーザがgazebo上のオブジェクト姿勢を変更しても良い
85  sleep_time = 3.0
86  print("Wait " + str(sleep_time) + " secs.")
87  rospy.sleep(sleep_time)
88  print("Start")
89 
90  # オブジェクトがgazebo上に存在すれば、pick_and_placeを実行する
91  if OBJECT_NAME in gazebo_model_states.name:
92  object_index = gazebo_model_states.name.index(OBJECT_NAME)
93  # オブジェクトの姿勢を取得
94  object_position = gazebo_model_states.pose[object_index].position
95  object_orientation = gazebo_model_states.pose[object_index].orientation
96  object_yaw = yaw_of(object_orientation)
97 
98  # オブジェクトに接近する
99  target_pose = Pose()
100  target_pose.position.x = object_position.x
101  target_pose.position.y = object_position.y
102  target_pose.position.z = APPROACH_Z
103  q = quaternion_from_euler(-math.pi, 0.0, object_yaw)
104  target_pose.orientation.x = q[0]
105  target_pose.orientation.y = q[1]
106  target_pose.orientation.z = q[2]
107  target_pose.orientation.w = q[3]
108  arm.set_pose_target(target_pose)
109  if arm.go() is False:
110  print("Failed to approach an object.")
111  continue
112  rospy.sleep(1.0)
113 
114  # 掴みに行く
115  target_pose.position.z = PICK_Z
116  arm.set_pose_target(target_pose)
117  if arm.go() is False:
118  print("Failed to grip an object.")
119  continue
120  rospy.sleep(1.0)
121  gripper_goal.command.position = GRIPPER_CLOSE
122  gripper.send_goal(gripper_goal)
123  gripper.wait_for_result(rospy.Duration(1.0))
124 
125  # 持ち上げる
126  target_pose.position.z = LEAVE_Z
127  arm.set_pose_target(target_pose)
128  if arm.go() is False:
129  print("Failed to pick up an object.")
130  continue
131  rospy.sleep(1.0)
132 
133  # 設置位置に移動する
134  place_position = random.choice(PLACE_POSITIONS) # 設置位置をランダムに選択する
135  target_pose.position.x = place_position.x
136  target_pose.position.y = place_position.y
137  q = quaternion_from_euler(-math.pi, 0.0, -math.pi/2.0)
138  target_pose.orientation.x = q[0]
139  target_pose.orientation.y = q[1]
140  target_pose.orientation.z = q[2]
141  target_pose.orientation.w = q[3]
142  arm.set_pose_target(target_pose)
143  if arm.go() is False:
144  print("Failed to approach target position.")
145  continue
146  rospy.sleep(1.0)
147 
148  # 設置する
149  target_pose.position.z = PICK_Z
150  arm.set_pose_target(target_pose)
151  if arm.go() is False:
152  print("Failed to place an object.")
153  continue
154  rospy.sleep(1.0)
155  gripper_goal.command.position = GRIPPER_OPEN
156  gripper.send_goal(gripper_goal)
157  gripper.wait_for_result(rospy.Duration(1.0))
158 
159  # ハンドを上げる
160  target_pose.position.z = LEAVE_Z
161  arm.set_pose_target(target_pose)
162  if arm.go() is False:
163  print("Failed to leave from an object.")
164  continue
165  rospy.sleep(1.0)
166 
167  # SRDFに定義されている"home"の姿勢にする
168  arm.set_named_target("home")
169  if arm.go() is False:
170  print("Failed to go back to home pose.")
171  continue
172  rospy.sleep(1.0)
173 
174  print("Done")
175 
176  else:
177  print("No objects")
178 
179 
180 if __name__ == '__main__':
181  rospy.init_node("pick_and_place_in_gazebo_example")
182 
183  try:
184  if not rospy.is_shutdown():
185  main()
186  except rospy.ROSInterruptException:
187  pass
pick_and_place_in_gazebo_example.callback
def callback(msg)
Definition: pick_and_place_in_gazebo_example.py:30
actionlib::SimpleActionClient
pick_and_place_in_gazebo_example.yaw_of
def yaw_of(object_orientation)
Definition: pick_and_place_in_gazebo_example.py:35
pick_and_place_in_gazebo_example.main
def main()
Definition: pick_and_place_in_gazebo_example.py:44


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