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


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