preset_pid_gain_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 moveit_commander
20 import geometry_msgs.msg
21 import rosnode
22 from tf.transformations import quaternion_from_euler
23 
24 from std_msgs.msg import UInt8
25 
26 def preset_pid_gain(pid_gain_no):
27  # サーボモータのPIDゲインをプリセットする
28  # プリセットの内容はcrane_x7_control/scripts/preset_reconfigure.pyに書かれている
29  rospy.loginfo("PID Gain Preset. No." + str(pid_gain_no))
30  preset_no = UInt8()
31  preset_no.data = pid_gain_no
32  pub_preset.publish(preset_no)
33  rospy.sleep(1) # PIDゲインがセットされるまで待つ
34 
35 
36 def main():
37  rospy.init_node("preset_pid_gain_example")
38  arm = moveit_commander.MoveGroupCommander("arm")
39  arm.set_max_velocity_scaling_factor(0.3)
40  arm.set_max_acceleration_scaling_factor(1.0)
41 
42  while len([s for s in rosnode.get_node_names() if 'rviz' in s]) == 0:
43  rospy.sleep(1.0)
44  rospy.sleep(1.0)
45 
46  # サーボモータのPIDゲインをプリセット
48 
49  # SRDFに定義されている"vertical"の姿勢にする
50  arm.set_named_target("vertical")
51  arm.go()
52  arm.set_named_target("home")
53  arm.go()
54 
55  # サーボモータのPIDゲインをプリセット
56  # Pゲインが小さくなるので、X7を手で動かすことが可能
58 
59  # X7を手で動かせることを確認するため、数秒間待つ
60  sleep_seconds = 10
61  for i in range(sleep_seconds):
62  rospy.loginfo(str(sleep_seconds-i) + " counts left.")
63  rospy.sleep(1)
64  # 安全のため、現在のアームの姿勢を目標姿勢に変更する
65  arm.set_pose_target(arm.get_current_pose())
66  arm.go()
67 
68  # サーボモータのPIDゲインをプリセット
70  arm.set_named_target("home")
71  arm.go()
72  arm.set_named_target("vertical")
73  arm.go()
74 
75  rospy.loginfo("done")
76 
77 
78 if __name__ == '__main__':
79  # PIDゲインプリセット用のPublisher
80  pub_preset = rospy.Publisher("preset_gain_no", UInt8, queue_size=1)
81 
82  try:
83  if not rospy.is_shutdown():
84  main()
85  except rospy.ROSInterruptException:
86  pass
preset_pid_gain_example.main
def main()
Definition: preset_pid_gain_example.py:36
preset_pid_gain_example.preset_pid_gain
def preset_pid_gain(pid_gain_no)
Definition: preset_pid_gain_example.py:26


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