6 import moveit_commander
10 arm = moveit_commander.MoveGroupCommander(
"arm")
12 arm.set_max_velocity_scaling_factor(0.5)
13 arm.set_max_acceleration_scaling_factor(1.0)
17 arm.set_named_target(
"vertical")
21 print(
"joint_value_target (radians):")
22 print(arm.get_joint_value_target())
23 print(
"current_joint_values (radians):")
24 print(arm.get_current_joint_values())
27 target_joint_values = arm.get_current_joint_values()
29 joint_angle = math.radians(-45)
31 target_joint_values[i] = joint_angle
32 arm.set_joint_value_target(target_joint_values)
34 print(str(i) +
"-> joint_value_target (degrees):" 35 + str(math.degrees(arm.get_joint_value_target()[i]))
36 +
", current_joint_values (degrees):" 37 + str(math.degrees(arm.get_current_joint_values()[i]))
42 arm.set_named_target(
"vertical")
46 if __name__ ==
'__main__':
47 rospy.init_node(
"joint_values_example")
50 if not rospy.is_shutdown():
52 except rospy.ROSInterruptException: