19 import moveit_commander
20 from std_msgs.msg
import UInt8
21 import sys, tty, termios, select
46 rospy.logwarn(
"Joint Values is nothing")
55 rospy.logwarn(
"Joint Values is nothing")
72 fd = sys.stdin.fileno()
73 old = termios.tcgetattr(fd)
76 (result_stdin, w, x) = select.select([sys.stdin], [], [], timeout)
78 return result_stdin[0].read(1)
84 termios.tcsetattr(fd, termios.TCSADRAIN, old)
90 rospy.loginfo(
"PID Gain Preset. No." + str(pid_gain_no))
92 preset_no.data = pid_gain_no
93 pub_preset.publish(preset_no)
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")
111 is_teaching_mode =
True
112 do_loop_playing =
False
115 gripper.set_joint_value_target([0.9, 0.9])
119 arm.set_named_target(
"home")
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
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")
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")
145 print(
"Keyboard input >>>")
149 input_key =
getch(0.1)
151 if input_key
is not False:
153 input_code = ord(input_key)
156 if input_code == CTRL_C
or input_code == ord(
'q')
or input_code == ord(
'Q'):
165 arm.set_pose_target(arm.get_current_pose())
167 gripper.set_joint_value_target(gripper.get_current_joint_values())
175 if input_code == ord(
'm')
or input_code == ord(
'M'):
177 is_teaching_mode =
not is_teaching_mode
187 arm.set_pose_target(arm.get_current_pose())
189 gripper.set_joint_value_target(gripper.get_current_joint_values())
199 if input_code == ord(
's')
or input_code == ord(
'S'):
200 print(
"Save joint values")
203 arm_joint_values = arm.get_current_joint_values()
204 gripper_joint_values = gripper.get_current_joint_values()
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?")
216 if input_code == ord(
'd')
or input_code == ord(
'D'):
217 print(
"\nDelete joint values")
218 data_base.delete_joint_values()
224 if input_code == ord(
'p')
or input_code == ord(
'P'):
226 joint_values = data_base.load_joint_values()
228 arm.set_joint_value_target(joint_values[0])
230 gripper.set_joint_value_target(joint_values[1])
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()
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])
244 gripper.set_joint_value_target(joint_values[1])
250 if input_code == ord(
'l')
or input_code == ord(
'L'):
253 do_loop_playing =
not do_loop_playing
266 joint_values = data_base.load_joint_values()
268 print(
"Play " + str(pose_index) +
" of " + str(poses_num))
270 arm.set_joint_value_target(joint_values[0])
272 gripper.set_joint_value_target(joint_values[1])
276 print(
"Loop play OFF")
277 do_loop_playing =
False
283 arm.set_named_target(
"vertical")
287 if __name__ ==
'__main__':
288 rospy.init_node(
"teaching_example")
293 pub_preset = rospy.Publisher(
"preset_gain_no", UInt8, queue_size=1)
296 if not rospy.is_shutdown():
298 except rospy.ROSInterruptException: