19 import moveit_commander
20 import geometry_msgs.msg
22 from tf.transformations
import quaternion_from_euler
24 from std_msgs.msg
import UInt8
29 rospy.loginfo(
"PID Gain Preset. No." + str(pid_gain_no))
31 preset_no.data = pid_gain_no
32 pub_preset.publish(preset_no)
37 rospy.init_node(
"preset_pid_gain_example")
38 arm = moveit_commander.MoveGroupCommander(
"arm")
39 arm.set_max_velocity_scaling_factor(0.3)
40 arm.set_max_acceleration_scaling_factor(1.0)
42 while len([s
for s
in rosnode.get_node_names()
if 'rviz' in s]) == 0:
50 arm.set_named_target(
"vertical")
52 arm.set_named_target(
"home")
61 for i
in range(sleep_seconds):
62 rospy.loginfo(str(sleep_seconds-i) +
" counts left.")
65 arm.set_pose_target(arm.get_current_pose())
70 arm.set_named_target(
"home")
72 arm.set_named_target(
"vertical")
78 if __name__ ==
'__main__':
80 pub_preset = rospy.Publisher(
"preset_gain_no", UInt8, queue_size=1)
83 if not rospy.is_shutdown():
85 except rospy.ROSInterruptException: