joystick_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 geometry_msgs.msg import Vector3, Quaternion
21 import rosnode
22 from tf.transformations import quaternion_from_euler, euler_from_quaternion
23 
24 import math
25 from sensor_msgs.msg import Joy
26 from geometry_msgs.msg import Pose
27 from std_msgs.msg import UInt8
28 
29 
30 class JoyWrapper(object):
31  def __init__(self):
32  self._sub_joy = rospy.Subscriber("joy", Joy, self._callback_joy, queue_size=1)
33 
34  self._grip_updated = False
35  self._pose_updated = False
36  self._name_updated = False
37  self._preset_updated = False
38  self._do_shutdown = False # ジョイスティックによる終了操作フラグ
39 
40  self.TEACHING_NONE = 0
41  self.TEACHING_SAVE = 1
42  self.TEACHING_LOAD = 2
43  self.TEACHING_DELETE = 3
45 
46  # /rane_x7_examples/launch/joystick_example.launch でキー割り当てを変更する
47  self._BUTTON_SHUTDOWN_1 = rospy.get_param("~button_shutdown_1")
48  self._BUTTON_SHUTDOWN_2 = rospy.get_param("~button_shutdown_2")
49 
50  self._BUTTON_NAME_ENABLE = rospy.get_param("~button_name_enable")
51  self._BUTTON_NAME_HOME = rospy.get_param("~button_name_home")
52 
53  self._BUTTON_PRESET_ENABLE = rospy.get_param("~button_preset_enable")
54  self._BUTTON_PRESET_NO1 = rospy.get_param("~button_preset_no1")
55 
56  self._BUTTON_TEACHING_ENABLE = rospy.get_param("~button_teaching_enable")
57  self._BUTTON_TEACHING_SAVE = rospy.get_param("~button_teaching_save")
58  self._BUTTON_TEACHING_LOAD = rospy.get_param("~button_teaching_load")
59  self._BUTTON_TEACHING_DELETE = rospy.get_param("~button_teaching_delete")
60 
61  self._BUTTON_GRIP_ENABLE = rospy.get_param("~button_grip_enable")
62  self._AXIS_GRIPPER = rospy.get_param("~axis_gripper")
63 
64  self._BUTTON_POSI_ENABLE = rospy.get_param("~button_posi_enable")
65  self._BUTTON_RPY_ENABLE = rospy.get_param("~button_rpy_enable")
66  self._AXIS_POSITION_X = rospy.get_param("~axis_position_x")
67  self._AXIS_POSITION_Y = rospy.get_param("~axis_position_y")
68  self._AXIS_POSITION_Z = rospy.get_param("~axis_position_z")
69 
70  # 目標姿勢
71  self._target_gripper_joint_values = [0.0, 0.0]
72  self._target_arm_pose = Pose()
73  self._target_arm_rpy = Vector3()
74  self._target_name = "vertical"
75 
76  # ティーチング
78  self._teaching_index = 0
79 
80  def set_target_gripper(self, joint_values):
81  self._target_gripper_joint_values = joint_values
82 
83  def set_target_arm(self, pose):
84  self._target_arm_pose = pose
85  self._target_arm_rpy = self._orientation_to_rpy(pose.pose.orientation)
86 
87  def get_target_gripper(self):
89 
90  def get_target_arm(self):
91  return self._target_arm_pose
92 
93  def get_target_name(self):
94  return self._target_name
95 
96  def do_shutdown(self):
97  return self._do_shutdown
98 
100  self._grip_updated, flag = False, self._grip_updated
101  return flag
102 
104  self._pose_updated, flag = False, self._pose_updated
105  return flag
106 
108  self._name_updated, flag = False, self._name_updated
109  return flag
110 
112  self._preset_updated, flag = False, self._preset_updated
113  return flag
114 
116  self._teaching_flag, flag = self.TEACHING_NONE, self._teaching_flag
117  return flag
118 
119  def save_joint_values(self, arm, gripper):
120  # ティーチング
121  # アームの各関節角度と、グリッパー開閉角度を配列に保存する
122  rospy.loginfo("Teaching. Save")
123  self._teaching_joint_values.append([arm, gripper])
124 
125  def load_joint_values(self):
126  # ティーチング
127  # 保存した角度情報を返す
128  # 配列のインデックスが末尾まで来たら、インデックスを0に戻す
129  # 何も保存していない場合はFalseを返す
130  if self._teaching_joint_values:
131  rospy.loginfo("Teaching. Load")
132  joint_values = self._teaching_joint_values[self._teaching_index]
133  self._teaching_index += 1
134 
135  if self._teaching_index >= len(self._teaching_joint_values):
136  rospy.loginfo("Teaching. Index reset")
137  self._teaching_index = 0
138  return joint_values
139  else:
140  rospy.logwarn("Teaching. Joint Values is nothing")
141  return False
142 
144  # ティーチング
145  # 角度情報が格納された配列を初期化する
146  rospy.loginfo("Teaching. Delete")
147  self._teaching_joint_values = []
148 
149  def _orientation_to_rpy(self, orientation):
150  # クォータニオンをRPY(Role, Pitch, Yaw)に変換する
151  x = orientation.x
152  y = orientation.y
153  z = orientation.z
154  w = orientation.w
155 
156  e = euler_from_quaternion((x, y, z, w))
157  return Vector3(e[0], e[1], e[2])
158 
159  def _rpy_to_orientation(self, rpy):
160  # RPY(Role, Pitch, Yaw)をクォータニオンに変換する
161  q = quaternion_from_euler(rpy.x, rpy.y, rpy.z)
162  return Quaternion(q[0], q[1], q[2], q[3])
163 
164  def _callback_joy(self, msg):
165  # ジョイスティック信号用のコールバック関数
166  # ボタン入力に合わせてフラグと制御量を設定する
167 
168  # シャットダウン
169  if msg.buttons[self._BUTTON_SHUTDOWN_1] and msg.buttons[self._BUTTON_SHUTDOWN_2]:
170  self._do_shutdown = True
171  return
172 
173  # Group State
174  if msg.buttons[self._BUTTON_NAME_ENABLE]:
175  if msg.buttons[self._BUTTON_NAME_HOME]:
176  self._target_name = "home"
177  self._name_updated = True
178  return
179 
180  # PIDゲインプリセット
181  if msg.buttons[self._BUTTON_PRESET_ENABLE]:
182  if msg.buttons[self._BUTTON_PRESET_NO1]:
183  self._preset_updated = True
184  return
185 
186  # ティーチングフラグ
187  if msg.buttons[self._BUTTON_TEACHING_ENABLE]:
188  if msg.buttons[self._BUTTON_TEACHING_SAVE]:
189  self._teaching_flag = self.TEACHING_SAVE
190  elif msg.buttons[self._BUTTON_TEACHING_LOAD]:
191  self._teaching_flag = self.TEACHING_LOAD
192  elif msg.buttons[self._BUTTON_TEACHING_DELETE]:
193  self._teaching_flag = self.TEACHING_DELETE
194  return
195 
196  # グリッパー開閉
197  if msg.buttons[self._BUTTON_GRIP_ENABLE]:
198  # ジョイスティックを倒した量に合わせて、グリッパーを閉じる
199  grip_value = 1.0 - math.fabs(msg.axes[self._AXIS_GRIPPER])
200 
201  if not grip_value:
202  grip_value = 0.01
203 
204  self._target_gripper_joint_values = [grip_value, grip_value]
205  self._grip_updated = True
206  return
207 
208  # アーム姿勢(位置)変更
209  if msg.buttons[self._BUTTON_POSI_ENABLE]:
210  # ジョイスティックを倒した量に合わせて、目標姿勢を変える
211  # ジョイスティックの仕様に合わせて、符号を変えてください
212  self._target_arm_pose.pose.position.x -= msg.axes[self._AXIS_POSITION_X] * 0.1
213  self._target_arm_pose.pose.position.y += msg.axes[self._AXIS_POSITION_Y] * 0.1
214  self._target_arm_pose.pose.position.z += msg.axes[self._AXIS_POSITION_Z] * 0.1
215  self._pose_updated = True
216 
217  # アーム姿勢(角度)変更
218  if msg.buttons[self._BUTTON_RPY_ENABLE]:
219  # ジョイスティックを倒した量に合わせて、目標姿勢を変える
220  # ジョイスティックの仕様に合わせて、符号を変えてください
221  self._target_arm_rpy.x -= msg.axes[self._AXIS_POSITION_X] * math.pi * 0.1
222  self._target_arm_rpy.y += msg.axes[self._AXIS_POSITION_Y] * math.pi * 0.1
223  self._target_arm_rpy.z += msg.axes[self._AXIS_POSITION_Z] * math.pi * 0.1
224  self._target_arm_pose.pose.orientation = self._rpy_to_orientation(self._target_arm_rpy)
225  self._pose_updated = True
226 
227 
228 def preset_pid_gain(pid_gain_no):
229  # サーボモータのPIDゲインをプリセットする
230  # プリセットの内容はcrane_x7_control/scripts/preset_reconfigure.pyに書かれている
231  rospy.loginfo("PID Gain Preset. No." + str(pid_gain_no))
232  preset_no = UInt8()
233  preset_no.data = pid_gain_no
234  pub_preset.publish(preset_no)
235  rospy.sleep(1) # PIDゲインがセットされるまで待つ
236 
237 
238 def main():
239  arm = moveit_commander.MoveGroupCommander("arm")
240  arm.set_max_velocity_scaling_factor(0.5)
241  arm.set_max_acceleration_scaling_factor(1.0)
242  gripper = moveit_commander.MoveGroupCommander("gripper")
243 
244  PRESET_DEFAULT = 0
245  PRESET_FREE = 3
246  pid_gain_no = PRESET_DEFAULT
247 
248 
249  # 何かを掴んでいた時のためにハンドを開く
250  gripper.set_joint_value_target([0.9, 0.9])
251  gripper.go()
252 
253  # SRDFに定義されている"home"の姿勢にする
254  arm.set_named_target("home")
255  arm.go()
256 
257  # 現在のアーム姿勢を、目標姿勢にセットする
258  joy_wrapper.set_target_arm(arm.get_current_pose())
259  joy_wrapper.set_target_gripper(gripper.get_current_joint_values())
260 
261 
262  while joy_wrapper.do_shutdown() == False:
263  # グリッパーの角度を変更する
264  if joy_wrapper.get_and_reset_grip_update_flag():
265  gripper.set_joint_value_target(joy_wrapper.get_target_gripper())
266  gripper.go()
267 
268  # アームの姿勢を変更する
269  if joy_wrapper.get_and_reset_pose_update_flag():
270  arm.set_pose_target(joy_wrapper.get_target_arm())
271  if arm.go() == False:
272  # 現在のアーム姿勢を、目標姿勢にセットする
273  joy_wrapper.set_target_arm(arm.get_current_pose())
274 
275  # アームの姿勢をpose_group (home or vertical)に変更する
276  if joy_wrapper.get_and_reset_name_update_flag():
277  arm.set_named_target(joy_wrapper.get_target_name())
278  arm.go()
279  # 現在のアーム姿勢を、目標姿勢にセットする
280  joy_wrapper.set_target_arm(arm.get_current_pose())
281 
282  # アームのPIDゲインをプリセットする
283  if joy_wrapper.get_and_reset_preset_update_flag():
284  # PIDゲインを0:default, 1:Free に切り替える
285  if pid_gain_no == PRESET_DEFAULT:
286  pid_gain_no = PRESET_FREE
287  else:
288  pid_gain_no = PRESET_DEFAULT
289  # PIDゲインをdefaultに戻すと、目標姿勢に向かって急に動き出す
290  # 安全のため、現在のアームの姿勢を目標姿勢に変更する
291  arm.set_pose_target(arm.get_current_pose())
292  arm.go()
293  preset_pid_gain(pid_gain_no)
294  # 現在のアーム姿勢を、目標姿勢にセットする
295  joy_wrapper.set_target_arm(arm.get_current_pose())
296 
297  # ティーチング
298  teaching_flag = joy_wrapper.get_and_reset_teaching_flag()
299  if teaching_flag == joy_wrapper.TEACHING_SAVE:
300  # 現在のアーム姿勢、グリッパー角度を保存する
301  # アームの角度が制御範囲内にない場合、例外が発生する
302  try:
303  arm_joint_values = arm.get_current_joint_values()
304  gripper_joint_values = gripper.get_current_joint_values()
305 
306  arm.set_joint_value_target(arm_joint_values)
307  gripper.set_joint_value_target(gripper_joint_values)
308  joy_wrapper.save_joint_values(arm_joint_values, gripper_joint_values)
310  print("Error setting joint target. Is the target within bounds?")
311  elif teaching_flag == joy_wrapper.TEACHING_LOAD:
312  # 保存したアーム、グリッパー角度を取り出す
313  joint_values = joy_wrapper.load_joint_values()
314  if joint_values:
315  arm.set_joint_value_target(joint_values[0])
316  arm.go()
317  gripper.set_joint_value_target(joint_values[1])
318  gripper.go()
319  # 現在のアーム姿勢を、目標姿勢にセットする
320  joy_wrapper.set_target_arm(arm.get_current_pose())
321  joy_wrapper.set_target_gripper(gripper.get_current_joint_values())
322  elif teaching_flag == joy_wrapper.TEACHING_DELETE:
323  # 保存したアーム姿勢、グリッパー角度を削除する
324  joy_wrapper.delete_joint_values()
325 
326 
327  rospy.loginfo("Shutdown...")
328 
329  # SRDFに定義されている"vertical"の姿勢にする
330  arm.set_named_target("vertical")
331  arm.go()
332 
333 
334 if __name__ == '__main__':
335  rospy.init_node("joystick_example")
336 
337  joy_wrapper = JoyWrapper()
338 
339  # PIDゲインプリセット用のPublisher
340  pub_preset = rospy.Publisher("preset_gain_no", UInt8, queue_size=1)
341 
342  try:
343  if not rospy.is_shutdown():
344  main()
345  except rospy.ROSInterruptException:
346  pass
joystick_example.JoyWrapper._BUTTON_TEACHING_ENABLE
_BUTTON_TEACHING_ENABLE
Definition: joystick_example.py:56
joystick_example.JoyWrapper._teaching_joint_values
_teaching_joint_values
Definition: joystick_example.py:77
joystick_example.JoyWrapper._BUTTON_GRIP_ENABLE
_BUTTON_GRIP_ENABLE
Definition: joystick_example.py:61
joystick_example.JoyWrapper.TEACHING_SAVE
TEACHING_SAVE
Definition: joystick_example.py:41
joystick_example.JoyWrapper._BUTTON_NAME_ENABLE
_BUTTON_NAME_ENABLE
Definition: joystick_example.py:50
joystick_example.JoyWrapper._AXIS_POSITION_Y
_AXIS_POSITION_Y
Definition: joystick_example.py:67
joystick_example.JoyWrapper.get_and_reset_grip_update_flag
def get_and_reset_grip_update_flag(self)
Definition: joystick_example.py:99
joystick_example.JoyWrapper.TEACHING_LOAD
TEACHING_LOAD
Definition: joystick_example.py:42
joystick_example.preset_pid_gain
def preset_pid_gain(pid_gain_no)
Definition: joystick_example.py:228
joystick_example.JoyWrapper._grip_updated
_grip_updated
Definition: joystick_example.py:34
joystick_example.JoyWrapper.__init__
def __init__(self)
Definition: joystick_example.py:31
joystick_example.JoyWrapper._do_shutdown
_do_shutdown
Definition: joystick_example.py:38
joystick_example.JoyWrapper._target_name
_target_name
Definition: joystick_example.py:74
joystick_example.JoyWrapper._rpy_to_orientation
def _rpy_to_orientation(self, rpy)
Definition: joystick_example.py:159
joystick_example.JoyWrapper._teaching_index
_teaching_index
Definition: joystick_example.py:78
joystick_example.JoyWrapper._BUTTON_RPY_ENABLE
_BUTTON_RPY_ENABLE
Definition: joystick_example.py:65
joystick_example.JoyWrapper._BUTTON_TEACHING_DELETE
_BUTTON_TEACHING_DELETE
Definition: joystick_example.py:59
joystick_example.JoyWrapper._BUTTON_PRESET_NO1
_BUTTON_PRESET_NO1
Definition: joystick_example.py:54
joystick_example.JoyWrapper.get_and_reset_preset_update_flag
def get_and_reset_preset_update_flag(self)
Definition: joystick_example.py:111
joystick_example.JoyWrapper.get_target_arm
def get_target_arm(self)
Definition: joystick_example.py:90
joystick_example.JoyWrapper._BUTTON_POSI_ENABLE
_BUTTON_POSI_ENABLE
Definition: joystick_example.py:64
joystick_example.JoyWrapper.save_joint_values
def save_joint_values(self, arm, gripper)
Definition: joystick_example.py:119
joystick_example.JoyWrapper._sub_joy
_sub_joy
Definition: joystick_example.py:32
joystick_example.JoyWrapper.delete_joint_values
def delete_joint_values(self)
Definition: joystick_example.py:143
joystick_example.JoyWrapper._orientation_to_rpy
def _orientation_to_rpy(self, orientation)
Definition: joystick_example.py:149
joystick_example.JoyWrapper._callback_joy
def _callback_joy(self, msg)
Definition: joystick_example.py:164
joystick_example.JoyWrapper._AXIS_POSITION_X
_AXIS_POSITION_X
Definition: joystick_example.py:66
joystick_example.JoyWrapper._BUTTON_PRESET_ENABLE
_BUTTON_PRESET_ENABLE
Definition: joystick_example.py:53
moveit_commander::exception::MoveItCommanderException
joystick_example.JoyWrapper.set_target_gripper
def set_target_gripper(self, joint_values)
Definition: joystick_example.py:80
joystick_example.JoyWrapper.get_and_reset_name_update_flag
def get_and_reset_name_update_flag(self)
Definition: joystick_example.py:107
joystick_example.JoyWrapper.do_shutdown
def do_shutdown(self)
Definition: joystick_example.py:96
joystick_example.JoyWrapper._AXIS_POSITION_Z
_AXIS_POSITION_Z
Definition: joystick_example.py:68
joystick_example.JoyWrapper._BUTTON_TEACHING_SAVE
_BUTTON_TEACHING_SAVE
Definition: joystick_example.py:57
joystick_example.JoyWrapper._teaching_flag
_teaching_flag
Definition: joystick_example.py:44
joystick_example.JoyWrapper._AXIS_GRIPPER
_AXIS_GRIPPER
Definition: joystick_example.py:62
joystick_example.JoyWrapper._target_arm_pose
_target_arm_pose
Definition: joystick_example.py:72
joystick_example.JoyWrapper._name_updated
_name_updated
Definition: joystick_example.py:36
joystick_example.JoyWrapper._BUTTON_SHUTDOWN_1
_BUTTON_SHUTDOWN_1
Definition: joystick_example.py:47
joystick_example.main
def main()
Definition: joystick_example.py:238
joystick_example.JoyWrapper.get_target_gripper
def get_target_gripper(self)
Definition: joystick_example.py:87
joystick_example.JoyWrapper._target_gripper_joint_values
_target_gripper_joint_values
Definition: joystick_example.py:71
joystick_example.JoyWrapper._target_arm_rpy
_target_arm_rpy
Definition: joystick_example.py:73
joystick_example.JoyWrapper.load_joint_values
def load_joint_values(self)
Definition: joystick_example.py:125
joystick_example.JoyWrapper
Definition: joystick_example.py:30
joystick_example.JoyWrapper._BUTTON_NAME_HOME
_BUTTON_NAME_HOME
Definition: joystick_example.py:51
joystick_example.JoyWrapper._BUTTON_SHUTDOWN_2
_BUTTON_SHUTDOWN_2
Definition: joystick_example.py:48
joystick_example.JoyWrapper.get_target_name
def get_target_name(self)
Definition: joystick_example.py:93
joystick_example.JoyWrapper.set_target_arm
def set_target_arm(self, pose)
Definition: joystick_example.py:83
joystick_example.JoyWrapper.get_and_reset_teaching_flag
def get_and_reset_teaching_flag(self)
Definition: joystick_example.py:115
joystick_example.JoyWrapper.TEACHING_NONE
TEACHING_NONE
Definition: joystick_example.py:40
joystick_example.JoyWrapper._pose_updated
_pose_updated
Definition: joystick_example.py:35
joystick_example.JoyWrapper._preset_updated
_preset_updated
Definition: joystick_example.py:37
joystick_example.JoyWrapper.get_and_reset_pose_update_flag
def get_and_reset_pose_update_flag(self)
Definition: joystick_example.py:103
joystick_example.JoyWrapper._BUTTON_TEACHING_LOAD
_BUTTON_TEACHING_LOAD
Definition: joystick_example.py:58
joystick_example.JoyWrapper.TEACHING_DELETE
TEACHING_DELETE
Definition: joystick_example.py:43


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