servo_info_example.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 import rospy
5 import moveit_commander
6 from std_msgs.msg import Int16, Float64
7 
8 # サーボの情報を格納するグローバル変数
9 gripper_current = 0.0
10 gripper_dxl_position = 0
11 gripper_temp = 0.0
12 
14  global gripper_current
15  gripper_current = msg.data
16 
18  global gripper_dxl_position
19  gripper_dxl_position = msg.data
20 
21 def temp_callback(msg):
22  global gripper_temp
23  gripper_temp = msg.data
24 
25 
26 def main():
27  global gripper_current
28  global gripper_dxl_position
29  global gripper_temp
30 
31  FULL_OPEN = 0.9
32  FULL_CLOSE = 0.01
33 
34  # 電流のしきい値を設定
35  CLOSE_THRESHOLD = 50
36  OPEN_THRESHOLD = -50
37 
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")
43 
44  # グリッパーを動かすサーボモータの電流値を取得
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)
47 
48  # グリッパーを動かすサーボモータの位置を取得
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)
51 
52  # グリッパーを動かすサーボモータの温度を取得
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)
55 
56 
57  # 何かを掴んでいた時のためにハンドを開く
58  gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
59  gripper.go()
60 
61  # SRDFに定義されている"home"の姿勢にする
62  arm.set_named_target("home")
63  arm.go()
64 
65  gripper_is_open = True
66 
67  r = rospy.Rate(60)
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))
72 
73  # 電流値がしきい値を超えれば、グリッパーを閉じる
74  if gripper_is_open is True and gripper_current > CLOSE_THRESHOLD:
75  gripper.set_joint_value_target([FULL_CLOSE, FULL_CLOSE])
76  gripper.go()
77  gripper_is_open = False
78 
79  # 電流値がしきい値を超えれば、グリッパーを開く
80  if gripper_is_open is False and gripper_current < OPEN_THRESHOLD:
81  gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
82  gripper.go()
83  gripper_is_open = True
84 
85  r.sleep()
86 
87  print("shutdown")
88 
89  # SRDFに定義されている"vertical"の姿勢にする
90  arm.set_named_target("vertical")
91  arm.go()
92 
93 
94 if __name__ == '__main__':
95  try:
96  if not rospy.is_shutdown():
97  main()
98  except rospy.ROSInterruptException:
99  pass


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Mar 1 2021 03:18:34