5 import moveit_commander
7 from std_msgs.msg
import UInt8
12 print(
"PID Gain Preset. No." + str(pid_gain_no))
14 preset_no.data = pid_gain_no
15 pub_preset.publish(preset_no)
20 rospy.init_node(
"preset_pid_gain_example")
21 arm = moveit_commander.MoveGroupCommander(
"r_arm_group")
22 arm.set_max_velocity_scaling_factor(0.1)
28 print(
"set named target : r_arm_init_pose")
29 arm.set_named_target(
"r_arm_init_pose")
38 for i
in range(sleep_seconds):
39 print( str(sleep_seconds-i) +
" counts left.")
42 arm.set_pose_target(arm.get_current_pose())
48 print(
"set named target : r_arm_init_pose")
49 arm.set_named_target(
"r_arm_init_pose")
55 if __name__ ==
'__main__':
57 pub_preset = rospy.Publisher(
"preset_gain_no", UInt8, queue_size=1)
60 if not rospy.is_shutdown():
62 except rospy.ROSInterruptException:
def preset_pid_gain(pid_gain_no)