pose_groupstate_example.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import rospy
5 import moveit_commander
6 import geometry_msgs.msg
7 import rosnode
8 from tf.transformations import quaternion_from_euler
9 
10 
11 def main():
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")
18 
19  while len([s for s in rosnode.get_node_names() if 'rviz' in s]) == 0:
20  rospy.sleep(1.0)
21  rospy.sleep(1.0)
22 
23  print("Group names:")
24  print(robot.get_group_names())
25 
26  print("Current state:")
27  print(robot.get_current_state())
28 
29  # アーム初期ポーズを表示
30  arm_initial_pose = arm.get_current_pose().pose
31  print("Arm initial pose:")
32  print(arm_initial_pose)
33 
34  # 何かを掴んでいた時のためにハンドを開く
35  gripper.set_joint_value_target([0.9, 0.9])
36  gripper.go()
37 
38  # SRDFに定義されている"home"の姿勢にする
39  print("home")
40  arm.set_named_target("home")
41  arm.go()
42 
43  # SRDFに定義されている"vertical"の姿勢にする
44  print("vertical")
45  arm.set_named_target("vertical")
46  arm.go()
47 
48  # ハンドを少し閉じる
49  gripper.set_joint_value_target([0.7, 0.7])
50  gripper.go()
51 
52  # 手動で姿勢を指定するには以下のように指定
53  """
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 ) # 目標ポーズ設定
64  arm.go() # 実行
65  """
66 
67  # 移動後の手先ポーズを表示
68  arm_goal_pose = arm.get_current_pose().pose
69  print("Arm goal pose:")
70  print(arm_goal_pose)
71  print("done")
72 
73 
74 if __name__ == '__main__':
75  try:
76  if not rospy.is_shutdown():
77  main()
78  except rospy.ROSInterruptException:
79  pass


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Mar 1 2021 03:18:34