preset_pid_gain_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 
7 from std_msgs.msg import UInt8
8 
9 def preset_pid_gain(pid_gain_no):
10  # サーボモータのPIDゲインをプリセットする
11  # プリセットの内容はsciurus7_control/scripts/preset_reconfigure.pyに書かれている
12  print("PID Gain Preset. No." + str(pid_gain_no))
13  preset_no = UInt8()
14  preset_no.data = pid_gain_no
15  pub_preset.publish(preset_no)
16  rospy.sleep(1) # PIDゲインがセットされるまで待つ
17 
18 
19 def main():
20  rospy.init_node("preset_pid_gain_example")
21  arm = moveit_commander.MoveGroupCommander("r_arm_group")
22  arm.set_max_velocity_scaling_factor(0.1)
23 
24  # サーボモータのPIDゲインをプリセット
26 
27  # SRDFに定義されている"r_arm_init_pose"の姿勢にする
28  print("set named target : r_arm_init_pose")
29  arm.set_named_target("r_arm_init_pose")
30  arm.go()
31 
32  # サーボモータのPIDゲインをプリセット
33  # Pゲインが小さくなるので、Sciurus17の右手を人間の手で動かすことが可能
35 
36  # 動作確認のため数秒間待つ
37  sleep_seconds = 10
38  for i in range(sleep_seconds):
39  print( str(sleep_seconds-i) + " counts left.")
40  rospy.sleep(1)
41  # 安全のため、現在の右手先姿勢を目標姿勢に変更する
42  arm.set_pose_target(arm.get_current_pose())
43  arm.go()
44 
45  # サーボモータのPIDゲインをプリセット
47 
48  print("set named target : r_arm_init_pose")
49  arm.set_named_target("r_arm_init_pose")
50  arm.go()
51 
52  print("done")
53 
54 
55 if __name__ == '__main__':
56  # PIDゲインプリセット用のPublisher
57  pub_preset = rospy.Publisher("preset_gain_no", UInt8, queue_size=1)
58 
59  try:
60  if not rospy.is_shutdown():
61  main()
62  except rospy.ROSInterruptException:
63  pass


sciurus17_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Sun Oct 2 2022 02:21:39