20 import moveit_commander
24 arm = moveit_commander.MoveGroupCommander(
"arm")
26 arm.set_max_velocity_scaling_factor(0.5)
27 arm.set_max_acceleration_scaling_factor(1.0)
31 arm.set_named_target(
"vertical")
35 print(
"joint_value_target (radians):")
36 print(arm.get_joint_value_target())
37 print(
"current_joint_values (radians):")
38 print(arm.get_current_joint_values())
41 target_joint_values = arm.get_current_joint_values()
43 joint_angle = math.radians(-45)
45 target_joint_values[i] = joint_angle
46 arm.set_joint_value_target(target_joint_values)
48 print(str(i) +
"-> joint_value_target (degrees):"
49 + str(math.degrees(arm.get_joint_value_target()[i]))
50 +
", current_joint_values (degrees):"
51 + str(math.degrees(arm.get_current_joint_values()[i]))
56 arm.set_named_target(
"vertical")
60 if __name__ ==
'__main__':
61 rospy.init_node(
"joint_values_example")
64 if not rospy.is_shutdown():
66 except rospy.ROSInterruptException: