pose_groupstate_example.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Copyright 2018 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 geometry_msgs.msg
21 import rosnode
22 from tf.transformations import quaternion_from_euler
23 
24 
25 def main():
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")
32 
33  while len([s for s in rosnode.get_node_names() if 'rviz' in s]) == 0:
34  rospy.sleep(1.0)
35  rospy.sleep(1.0)
36 
37  print("Group names:")
38  print(robot.get_group_names())
39 
40  print("Current state:")
41  print(robot.get_current_state())
42 
43  # アーム初期ポーズを表示
44  arm_initial_pose = arm.get_current_pose().pose
45  print("Arm initial pose:")
46  print(arm_initial_pose)
47 
48  # 何かを掴んでいた時のためにハンドを開く
49  gripper.set_joint_value_target([0.9, 0.9])
50  gripper.go()
51 
52  # SRDFに定義されている"home"の姿勢にする
53  print("home")
54  arm.set_named_target("home")
55  arm.go()
56 
57  # SRDFに定義されている"vertical"の姿勢にする
58  print("vertical")
59  arm.set_named_target("vertical")
60  arm.go()
61 
62  # ハンドを少し閉じる
63  gripper.set_joint_value_target([0.7, 0.7])
64  gripper.go()
65 
66  # 手動で姿勢を指定するには以下のように指定
67  """
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 ) # 目標ポーズ設定
78  arm.go() # 実行
79  """
80 
81  # 移動後の手先ポーズを表示
82  arm_goal_pose = arm.get_current_pose().pose
83  print("Arm goal pose:")
84  print(arm_goal_pose)
85  print("done")
86 
87 
88 if __name__ == '__main__':
89  try:
90  if not rospy.is_shutdown():
91  main()
92  except rospy.ROSInterruptException:
93  pass
pose_groupstate_example.main
def main()
Definition: pose_groupstate_example.py:25


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