19 import moveit_commander
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
28 gazebo_model_states = ModelStates()
31 global gazebo_model_states
32 gazebo_model_states = msg
37 euler = euler_from_quaternion(
38 (object_orientation.x, object_orientation.y,
39 object_orientation.z, object_orientation.w))
45 global gazebo_model_states
47 OBJECT_NAME =
"wood_cube_5cm"
56 Point(0.0, -0.3, 0.0),
58 Point(0.2, -0.2, 0.0)]
60 sub_model_states = rospy.Subscriber(
"gazebo/model_states", ModelStates, callback, queue_size=1)
62 arm = moveit_commander.MoveGroupCommander(
"arm")
63 arm.set_max_velocity_scaling_factor(0.4)
64 arm.set_max_acceleration_scaling_factor(1.0)
66 gripper.wait_for_server()
67 gripper_goal = GripperCommandGoal()
68 gripper_goal.command.max_effort = 4.0
74 gripper_goal.command.position = GRIPPER_OPEN
75 gripper.send_goal(gripper_goal)
76 gripper.wait_for_result(rospy.Duration(1.0))
79 arm.set_named_target(
"home")
86 print(
"Wait " + str(sleep_time) +
" secs.")
87 rospy.sleep(sleep_time)
91 if OBJECT_NAME
in gazebo_model_states.name:
92 object_index = gazebo_model_states.name.index(OBJECT_NAME)
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)
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.")
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.")
121 gripper_goal.command.position = GRIPPER_CLOSE
122 gripper.send_goal(gripper_goal)
123 gripper.wait_for_result(rospy.Duration(1.0))
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.")
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.")
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.")
155 gripper_goal.command.position = GRIPPER_OPEN
156 gripper.send_goal(gripper_goal)
157 gripper.wait_for_result(rospy.Duration(1.0))
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.")
168 arm.set_named_target(
"home")
169 if arm.go()
is False:
170 print(
"Failed to go back to home pose.")
180 if __name__ ==
'__main__':
181 rospy.init_node(
"pick_and_place_in_gazebo_example")
184 if not rospy.is_shutdown():
186 except rospy.ROSInterruptException: