5 import moveit_commander
6 from std_msgs.msg
import Int16, Float64
10 gripper_dxl_position = 0
14 global gripper_current
15 gripper_current = msg.data
18 global gripper_dxl_position
19 gripper_dxl_position = msg.data
23 gripper_temp = msg.data
27 global gripper_current
28 global gripper_dxl_position
38 rospy.init_node(
"joystick_example")
39 arm = moveit_commander.MoveGroupCommander(
"arm")
40 arm.set_max_velocity_scaling_factor(0.3)
41 arm.set_max_acceleration_scaling_factor(1.0)
42 gripper = moveit_commander.MoveGroupCommander(
"gripper")
45 sub_gripper_current = rospy.Subscriber(
"/crane_x7/crane_x7_control/crane_x7_gripper_finger_a_joint/current",
46 Float64, current_callback, queue_size=1)
49 sub_gripper_dxl_position = rospy.Subscriber(
"/crane_x7/crane_x7_control/crane_x7_gripper_finger_a_joint/dxl_position",
50 Int16, dxl_position_callback, queue_size=1)
53 sub_gripper_temp = rospy.Subscriber(
"/crane_x7/crane_x7_control/crane_x7_gripper_finger_a_joint/temp",
54 Float64, temp_callback, queue_size=1)
58 gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
62 arm.set_named_target(
"home")
65 gripper_is_open =
True 68 while not rospy.is_shutdown():
69 print(
" current [mA]: " + str(gripper_current).ljust(6)
70 +
" dxl_position: " + str(gripper_dxl_position).ljust(6)
71 +
" temp [deg C]: " + str(gripper_temp).ljust(6))
74 if gripper_is_open
is True and gripper_current > CLOSE_THRESHOLD:
75 gripper.set_joint_value_target([FULL_CLOSE, FULL_CLOSE])
77 gripper_is_open =
False 80 if gripper_is_open
is False and gripper_current < OPEN_THRESHOLD:
81 gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
83 gripper_is_open =
True 90 arm.set_named_target(
"vertical")
94 if __name__ ==
'__main__':
96 if not rospy.is_shutdown():
98 except rospy.ROSInterruptException:
def dxl_position_callback(msg)
def current_callback(msg)