19 import moveit_commander
20 from std_msgs.msg
import Int16, Float64
24 gripper_dxl_position = 0
28 global gripper_current
29 gripper_current = msg.data
32 global gripper_dxl_position
33 gripper_dxl_position = msg.data
37 gripper_temp = msg.data
41 global gripper_current
42 global gripper_dxl_position
52 rospy.init_node(
"joystick_example")
53 arm = moveit_commander.MoveGroupCommander(
"arm")
54 arm.set_max_velocity_scaling_factor(0.3)
55 arm.set_max_acceleration_scaling_factor(1.0)
56 gripper = moveit_commander.MoveGroupCommander(
"gripper")
59 sub_gripper_current = rospy.Subscriber(
"/crane_x7/crane_x7_control/crane_x7_gripper_finger_a_joint/current",
60 Float64, current_callback, queue_size=1)
63 sub_gripper_dxl_position = rospy.Subscriber(
"/crane_x7/crane_x7_control/crane_x7_gripper_finger_a_joint/dxl_position",
64 Int16, dxl_position_callback, queue_size=1)
67 sub_gripper_temp = rospy.Subscriber(
"/crane_x7/crane_x7_control/crane_x7_gripper_finger_a_joint/temp",
68 Float64, temp_callback, queue_size=1)
72 gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
76 arm.set_named_target(
"home")
79 gripper_is_open =
True
82 while not rospy.is_shutdown():
83 print(
" current [mA]: " + str(gripper_current).ljust(6)
84 +
" dxl_position: " + str(gripper_dxl_position).ljust(6)
85 +
" temp [deg C]: " + str(gripper_temp).ljust(6))
88 if gripper_is_open
is True and gripper_current > CLOSE_THRESHOLD:
89 gripper.set_joint_value_target([FULL_CLOSE, FULL_CLOSE])
91 gripper_is_open =
False
94 if gripper_is_open
is False and gripper_current < OPEN_THRESHOLD:
95 gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
97 gripper_is_open =
True
104 arm.set_named_target(
"vertical")
108 if __name__ ==
'__main__':
110 if not rospy.is_shutdown():
112 except rospy.ROSInterruptException: