19 import moveit_commander
20 import geometry_msgs.msg
22 from tf.transformations
import quaternion_from_euler
26 rospy.init_node(
"pose_groupstate_example")
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")
33 while len([s
for s
in rosnode.get_node_names()
if 'rviz' in s]) == 0:
38 print(robot.get_group_names())
40 print(
"Current state:")
41 print(robot.get_current_state())
44 arm_initial_pose = arm.get_current_pose().pose
45 print(
"Arm initial pose:")
46 print(arm_initial_pose)
49 gripper.set_joint_value_target([0.9, 0.9])
54 arm.set_named_target(
"home")
59 arm.set_named_target(
"vertical")
63 gripper.set_joint_value_target([0.7, 0.7])
68 target_pose = geometry_msgs.msg.Pose()
69 target_pose.position.x = 0.0
70 target_pose.position.y = 0.0
71 target_pose.position.z = 0.624
72 q = quaternion_from_euler( 0.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 ) # 目標ポーズ設定
82 arm_goal_pose = arm.get_current_pose().pose
83 print(
"Arm goal pose:")
88 if __name__ ==
'__main__':
90 if not rospy.is_shutdown():
92 except rospy.ROSInterruptException: