19 import moveit_commander
20 from geometry_msgs.msg
import Vector3, Quaternion
22 from tf.transformations
import quaternion_from_euler, euler_from_quaternion
25 from sensor_msgs.msg
import Joy
26 from geometry_msgs.msg
import Pose
27 from std_msgs.msg
import UInt8
122 rospy.loginfo(
"Teaching. Save")
131 rospy.loginfo(
"Teaching. Load")
136 rospy.loginfo(
"Teaching. Index reset")
140 rospy.logwarn(
"Teaching. Joint Values is nothing")
146 rospy.loginfo(
"Teaching. Delete")
156 e = euler_from_quaternion((x, y, z, w))
157 return Vector3(e[0], e[1], e[2])
161 q = quaternion_from_euler(rpy.x, rpy.y, rpy.z)
162 return Quaternion(q[0], q[1], q[2], q[3])
231 rospy.loginfo(
"PID Gain Preset. No." + str(pid_gain_no))
233 preset_no.data = pid_gain_no
234 pub_preset.publish(preset_no)
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")
246 pid_gain_no = PRESET_DEFAULT
250 gripper.set_joint_value_target([0.9, 0.9])
254 arm.set_named_target(
"home")
258 joy_wrapper.set_target_arm(arm.get_current_pose())
259 joy_wrapper.set_target_gripper(gripper.get_current_joint_values())
262 while joy_wrapper.do_shutdown() ==
False:
264 if joy_wrapper.get_and_reset_grip_update_flag():
265 gripper.set_joint_value_target(joy_wrapper.get_target_gripper())
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:
273 joy_wrapper.set_target_arm(arm.get_current_pose())
276 if joy_wrapper.get_and_reset_name_update_flag():
277 arm.set_named_target(joy_wrapper.get_target_name())
280 joy_wrapper.set_target_arm(arm.get_current_pose())
283 if joy_wrapper.get_and_reset_preset_update_flag():
285 if pid_gain_no == PRESET_DEFAULT:
286 pid_gain_no = PRESET_FREE
288 pid_gain_no = PRESET_DEFAULT
291 arm.set_pose_target(arm.get_current_pose())
295 joy_wrapper.set_target_arm(arm.get_current_pose())
298 teaching_flag = joy_wrapper.get_and_reset_teaching_flag()
299 if teaching_flag == joy_wrapper.TEACHING_SAVE:
303 arm_joint_values = arm.get_current_joint_values()
304 gripper_joint_values = gripper.get_current_joint_values()
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:
313 joint_values = joy_wrapper.load_joint_values()
315 arm.set_joint_value_target(joint_values[0])
317 gripper.set_joint_value_target(joint_values[1])
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:
324 joy_wrapper.delete_joint_values()
327 rospy.loginfo(
"Shutdown...")
330 arm.set_named_target(
"vertical")
334 if __name__ ==
'__main__':
335 rospy.init_node(
"joystick_example")
340 pub_preset = rospy.Publisher(
"preset_gain_no", UInt8, queue_size=1)
343 if not rospy.is_shutdown():
345 except rospy.ROSInterruptException: