5 import moveit_commander
6 import geometry_msgs.msg
8 from tf.transformations
import quaternion_from_euler
12 rospy.init_node(
"pose_groupstate_example")
13 robot = moveit_commander.RobotCommander()
14 arm = moveit_commander.MoveGroupCommander(
"arm")
15 arm.set_max_velocity_scaling_factor(0.1)
16 arm.set_max_acceleration_scaling_factor(1.0)
17 gripper = moveit_commander.MoveGroupCommander(
"gripper")
19 while len([s
for s
in rosnode.get_node_names()
if 'rviz' in s]) == 0:
24 print(robot.get_group_names())
26 print(
"Current state:")
27 print(robot.get_current_state())
30 arm_initial_pose = arm.get_current_pose().pose
31 print(
"Arm initial pose:")
32 print(arm_initial_pose)
35 gripper.set_joint_value_target([0.9, 0.9])
40 arm.set_named_target(
"home")
45 arm.set_named_target(
"vertical")
49 gripper.set_joint_value_target([0.7, 0.7])
54 target_pose = geometry_msgs.msg.Pose() 55 target_pose.position.x = 0.0 56 target_pose.position.y = 0.0 57 target_pose.position.z = 0.624 58 q = quaternion_from_euler( 0.0, 0.0, 0.0 ) 59 target_pose.orientation.x = q[0] 60 target_pose.orientation.y = q[1] 61 target_pose.orientation.z = q[2] 62 target_pose.orientation.w = q[3] 63 arm.set_pose_target( target_pose ) # 目標ポーズ設定 68 arm_goal_pose = arm.get_current_pose().pose
69 print(
"Arm goal pose:")
74 if __name__ ==
'__main__':
76 if not rospy.is_shutdown():
78 except rospy.ROSInterruptException: