teaching_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 from std_msgs.msg import UInt8
21 import sys, tty, termios, select
22 
23 
24 class TeachingDataBase(object):
25  def __init__(self):
26 
28  self._teaching_index = 0
29 
30  def save_joint_values(self, arm, gripper):
31  # アームの各関節角度と、グリッパー開閉角度を配列に保存する
32  self._teaching_joint_values.append([arm, gripper])
33 
34  def load_joint_values(self):
35  # 保存した角度情報を返す
36  # 配列のインデックスが末尾まで来たら、インデックスを0に戻す
37  # 何も保存していない場合はFalseを返す
38  if self._teaching_joint_values:
39  joint_values = self._teaching_joint_values[self._teaching_index]
40  self._teaching_index += 1
41 
42  if self._teaching_index >= len(self._teaching_joint_values):
43  self._teaching_index = 0
44  return joint_values
45  else:
46  rospy.logwarn("Joint Values is nothing")
47  return False
48 
50  # 保存した角度情報をすべて返す
51  # 何も保存していない場合はFalseを返す
52  if self._teaching_joint_values:
53  return self._teaching_joint_values
54  else:
55  rospy.logwarn("Joint Values is nothing")
56  return False
57 
59  # 角度情報が格納された配列を初期化する
60  self._teaching_joint_values = []
61  self._teaching_index = 0
62 
63  def get_current_index(self):
64  return self._teaching_index
65 
66  def get_num_of_poses(self):
67  return len(self._teaching_joint_values)
68 
69 
70 def getch(timeout):
71  # 1文字のキーボード入力を返す
72  fd = sys.stdin.fileno()
73  old = termios.tcgetattr(fd)
74  try:
75  tty.setraw(fd)
76  (result_stdin, w, x) = select.select([sys.stdin], [], [], timeout)
77  if len(result_stdin):
78  return result_stdin[0].read(1)
79  else:
80  return False
81 
82  # return sys.stdin.read(1)
83  finally:
84  termios.tcsetattr(fd, termios.TCSADRAIN, old)
85 
86 
87 def preset_pid_gain(pid_gain_no):
88  # サーボモータのPIDゲインをプリセットする
89  # プリセットの内容はcrane_x7_control/scripts/preset_reconfigure.pyに書かれている
90  rospy.loginfo("PID Gain Preset. No." + str(pid_gain_no))
91  preset_no = UInt8()
92  preset_no.data = pid_gain_no
93  pub_preset.publish(preset_no)
94  rospy.sleep(1) # PIDゲインがセットされるまで待つ
95 
96 
97 def main():
98  arm = moveit_commander.MoveGroupCommander("arm")
99  arm.set_max_velocity_scaling_factor(0.5)
100  arm.set_max_acceleration_scaling_factor(1.0)
101  gripper = moveit_commander.MoveGroupCommander("gripper")
102 
103  TORQUE_ON_PID = 0
104  TORQUE_OFF_PID = 3
105 
106  CTRL_C = 3 # Unicode Code
107 
108  input_code = 0
109  do_shutdown = False
110  do_restart = True
111  is_teaching_mode = True
112  do_loop_playing = False
113 
114  # 何かを掴んでいた時のためにハンドを開く
115  gripper.set_joint_value_target([0.9, 0.9])
116  gripper.go()
117 
118  # SRDFに定義されている"home"の姿勢にする
119  arm.set_named_target("home")
120  arm.go()
121 
122  # preset_reconfigureノードが起動するまで待機
123  rospy.sleep(1)
124 
125  # トルクをオフにする
126  preset_pid_gain(TORQUE_OFF_PID)
127  print("Torque OFF")
128 
129  while do_shutdown is False:
130  poses_num = data_base.get_num_of_poses()
131  pose_index = data_base.get_current_index() + 1 if poses_num else 0
132 
133  # リスタート時はキーボード入力の説明を表示
134  if do_restart:
135  print("")
136  if is_teaching_mode:
137  print("[Teaching Mode]"
138  + "[Next Pose:" + str(pose_index) + " of " + str(poses_num) + "]")
139  print("[q]: Quit, [m]: switch to action Mode, [s]: Save, [d]: Delete")
140  else:
141  print("[Action Mode]"
142  + "[Next Pose:" + str(pose_index) + " of " + str(poses_num) + "]")
143  print("[q]: Quit, [m]: switch to teaching Mode, [p]: Play 1 pose, [a]: play All pose, [l]: Loop play on/off")
144 
145  print("Keyboard input >>>")
146  do_restart = False
147 
148  # 文字入力
149  input_key = getch(0.1) # 一定時間入力がなければFalseを返す
150  input_code = ""
151  if input_key is not False:
152  print(input_key)
153  input_code = ord(input_key)
154 
155  # シャットダウン
156  if input_code == CTRL_C or input_code == ord('q') or input_code == ord('Q'):
157  print("Shutdown...")
158 
159  # トルクをONにしてから終了する
160  if is_teaching_mode:
161  print("Torque ON")
162  # PIDゲインをdefaultに戻すと、目標姿勢に向かって急に動き出す
163  # 安全のため、現在のアームの姿勢を目標姿勢に変更する
164  rospy.sleep(1)
165  arm.set_pose_target(arm.get_current_pose())
166  arm.go()
167  gripper.set_joint_value_target(gripper.get_current_joint_values())
168  gripper.go()
169  preset_pid_gain(TORQUE_ON_PID)
170 
171  do_shutdown = True
172  continue
173 
174  # モード切替
175  if input_code == ord('m') or input_code == ord('M'):
176  print("Mode switch")
177  is_teaching_mode = not is_teaching_mode
178 
179  if is_teaching_mode:
180  print("Torque OFF")
181  preset_pid_gain(TORQUE_OFF_PID)
182  else:
183  print("Torque ON")
184  # PIDゲインをdefaultに戻すと、目標姿勢に向かって急に動き出す
185  # 安全のため、現在のアームの姿勢を目標姿勢に変更する
186  rospy.sleep(1)
187  arm.set_pose_target(arm.get_current_pose())
188  arm.go()
189  gripper.set_joint_value_target(gripper.get_current_joint_values())
190  gripper.go()
191  preset_pid_gain(TORQUE_ON_PID)
192 
193  do_restart = True
194  continue
195 
196 
197  if is_teaching_mode:
198  # 現在のアーム姿勢、グリッパー角度を保存する
199  if input_code == ord('s') or input_code == ord('S'):
200  print("Save joint values")
201  # アームの角度が制御範囲内にない場合、例外が発生する
202  try:
203  arm_joint_values = arm.get_current_joint_values()
204  gripper_joint_values = gripper.get_current_joint_values()
205 
206  arm.set_joint_value_target(arm_joint_values)
207  gripper.set_joint_value_target(gripper_joint_values)
208  data_base.save_joint_values(arm_joint_values, gripper_joint_values)
210  print("Error setting joint target. Is the target within bounds?")
211 
212  do_restart = True
213  continue
214 
215  # 保存したアーム姿勢、グリッパー角度を削除する
216  if input_code == ord('d') or input_code == ord('D'):
217  print("\nDelete joint values")
218  data_base.delete_joint_values()
219  do_restart = True
220  continue
221 
222  else:
223  # 保存したアーム、グリッパー角度を取り出す
224  if input_code == ord('p') or input_code == ord('P'):
225  print("Play 1 pose")
226  joint_values = data_base.load_joint_values()
227  if joint_values:
228  arm.set_joint_value_target(joint_values[0])
229  arm.go()
230  gripper.set_joint_value_target(joint_values[1])
231  gripper.go()
232  do_restart = True
233  continue
234 
235  # 保存したアーム、グリッパー角度を連続再生する
236  if input_code == ord('a') or input_code == ord('A'):
237  print("play All poses")
238  all_joint_values = data_base.load_all_joint_values()
239  if all_joint_values:
240  for i, joint_values in enumerate(all_joint_values):
241  print("Play: " + str(i+1) + " of " + str(poses_num))
242  arm.set_joint_value_target(joint_values[0])
243  arm.go()
244  gripper.set_joint_value_target(joint_values[1])
245  gripper.go()
246  do_restart = True
247  continue
248 
249  # 保存したアーム、グリッパー角度をループ再生する
250  if input_code == ord('l') or input_code == ord('L'):
251  print("Loop play")
252 
253  do_loop_playing = not do_loop_playing
254 
255  if do_loop_playing:
256  print("ON")
257  else:
258  print("OFF")
259  # 再び再生しないようにsleepを設ける
260  rospy.sleep(1)
261  do_restart = True
262  continue
263 
264  # ループ再生
265  if do_loop_playing:
266  joint_values = data_base.load_joint_values()
267  if joint_values:
268  print("Play " + str(pose_index) + " of " + str(poses_num))
269 
270  arm.set_joint_value_target(joint_values[0])
271  arm.go()
272  gripper.set_joint_value_target(joint_values[1])
273  gripper.go()
274  else:
275  # 姿勢が保存されていなかったらループ再生を終了する
276  print("Loop play OFF")
277  do_loop_playing = False
278  do_restart = True
279  continue
280 
281 
282  # SRDFに定義されている"vertical"の姿勢にする
283  arm.set_named_target("vertical")
284  arm.go()
285 
286 
287 if __name__ == '__main__':
288  rospy.init_node("teaching_example")
289 
290  data_base = TeachingDataBase()
291 
292  # PIDゲインプリセット用のPublisher
293  pub_preset = rospy.Publisher("preset_gain_no", UInt8, queue_size=1)
294 
295  try:
296  if not rospy.is_shutdown():
297  main()
298  except rospy.ROSInterruptException:
299  pass
teaching_example.TeachingDataBase._teaching_index
_teaching_index
Definition: teaching_example.py:28
teaching_example.TeachingDataBase.get_num_of_poses
def get_num_of_poses(self)
Definition: teaching_example.py:66
teaching_example.TeachingDataBase._teaching_joint_values
_teaching_joint_values
Definition: teaching_example.py:27
teaching_example.preset_pid_gain
def preset_pid_gain(pid_gain_no)
Definition: teaching_example.py:87
teaching_example.TeachingDataBase.get_current_index
def get_current_index(self)
Definition: teaching_example.py:63
teaching_example.TeachingDataBase
Definition: teaching_example.py:24
moveit_commander::exception::MoveItCommanderException
teaching_example.TeachingDataBase.__init__
def __init__(self)
Definition: teaching_example.py:25
teaching_example.getch
def getch(timeout)
Definition: teaching_example.py:70
teaching_example.main
def main()
Definition: teaching_example.py:97
teaching_example.TeachingDataBase.save_joint_values
def save_joint_values(self, arm, gripper)
Definition: teaching_example.py:30
teaching_example.TeachingDataBase.delete_joint_values
def delete_joint_values(self)
Definition: teaching_example.py:58
teaching_example.TeachingDataBase.load_joint_values
def load_joint_values(self)
Definition: teaching_example.py:34
teaching_example.TeachingDataBase.load_all_joint_values
def load_all_joint_values(self)
Definition: teaching_example.py:49


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