joint_values_example.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Copyright 2019 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 math
20 import moveit_commander
21 
22 
23 def main():
24  arm = moveit_commander.MoveGroupCommander("arm")
25  # 駆動速度を調整する
26  arm.set_max_velocity_scaling_factor(0.5)
27  arm.set_max_acceleration_scaling_factor(1.0)
28 
29  # SRDFに定義されている"vertical"の姿勢にする
30  # すべてのジョイントの目標角度が0度になる
31  arm.set_named_target("vertical")
32  arm.go()
33 
34  # 目標角度と実際の角度を確認
35  print("joint_value_target (radians):")
36  print(arm.get_joint_value_target())
37  print("current_joint_values (radians):")
38  print(arm.get_current_joint_values())
39 
40  # 現在角度をベースに、目標角度を作成する
41  target_joint_values = arm.get_current_joint_values()
42  # 各ジョイントの角度を1つずつ変更する
43  joint_angle = math.radians(-45)
44  for i in range(7):
45  target_joint_values[i] = joint_angle
46  arm.set_joint_value_target(target_joint_values)
47  arm.go()
48  print(str(i) + "-> joint_value_target (degrees):"
49  + str(math.degrees(arm.get_joint_value_target()[i]))
50  + ", current_joint_values (degrees):"
51  + str(math.degrees(arm.get_current_joint_values()[i]))
52  )
53 
54  rospy.sleep(3)
55  # 垂直に戻す
56  arm.set_named_target("vertical")
57  arm.go()
58 
59 
60 if __name__ == '__main__':
61  rospy.init_node("joint_values_example")
62 
63  try:
64  if not rospy.is_shutdown():
65  main()
66  except rospy.ROSInterruptException:
67  pass
joint_values_example.main
def main()
Definition: joint_values_example.py:23


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