servo_info_example.py
Go to the documentation of this file.
1 #! /usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 # Copyright 2019 RT Corporation
5 #
6 # Licensed under the Apache License, Version 2.0 (the "License");
7 # you may not use this file except in compliance with the License.
8 # You may obtain a copy of the License at
9 #
10 # http://www.apache.org/licenses/LICENSE-2.0
11 #
12 # Unless required by applicable law or agreed to in writing, software
13 # distributed under the License is distributed on an "AS IS" BASIS,
14 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
15 # See the License for the specific language governing permissions and
16 # limitations under the License.
17 
18 import rospy
19 import moveit_commander
20 from std_msgs.msg import Int16, Float64
21 
22 # サーボの情報を格納するグローバル変数
23 gripper_current = 0.0
24 gripper_dxl_position = 0
25 gripper_temp = 0.0
26 
28  global gripper_current
29  gripper_current = msg.data
30 
32  global gripper_dxl_position
33  gripper_dxl_position = msg.data
34 
35 def temp_callback(msg):
36  global gripper_temp
37  gripper_temp = msg.data
38 
39 
40 def main():
41  global gripper_current
42  global gripper_dxl_position
43  global gripper_temp
44 
45  FULL_OPEN = 0.9
46  FULL_CLOSE = 0.01
47 
48  # 電流のしきい値を設定
49  CLOSE_THRESHOLD = 50
50  OPEN_THRESHOLD = -50
51 
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")
57 
58  # グリッパーを動かすサーボモータの電流値を取得
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)
61 
62  # グリッパーを動かすサーボモータの位置を取得
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)
65 
66  # グリッパーを動かすサーボモータの温度を取得
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)
69 
70 
71  # 何かを掴んでいた時のためにハンドを開く
72  gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
73  gripper.go()
74 
75  # SRDFに定義されている"home"の姿勢にする
76  arm.set_named_target("home")
77  arm.go()
78 
79  gripper_is_open = True
80 
81  r = rospy.Rate(60)
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))
86 
87  # 電流値がしきい値を超えれば、グリッパーを閉じる
88  if gripper_is_open is True and gripper_current > CLOSE_THRESHOLD:
89  gripper.set_joint_value_target([FULL_CLOSE, FULL_CLOSE])
90  gripper.go()
91  gripper_is_open = False
92 
93  # 電流値がしきい値を超えれば、グリッパーを開く
94  if gripper_is_open is False and gripper_current < OPEN_THRESHOLD:
95  gripper.set_joint_value_target([FULL_OPEN, FULL_OPEN])
96  gripper.go()
97  gripper_is_open = True
98 
99  r.sleep()
100 
101  print("shutdown")
102 
103  # SRDFに定義されている"vertical"の姿勢にする
104  arm.set_named_target("vertical")
105  arm.go()
106 
107 
108 if __name__ == '__main__':
109  try:
110  if not rospy.is_shutdown():
111  main()
112  except rospy.ROSInterruptException:
113  pass
servo_info_example.temp_callback
def temp_callback(msg)
Definition: servo_info_example.py:35
servo_info_example.current_callback
def current_callback(msg)
Definition: servo_info_example.py:27
servo_info_example.dxl_position_callback
def dxl_position_callback(msg)
Definition: servo_info_example.py:31
servo_info_example.main
def main()
Definition: servo_info_example.py:40


crane_x7_examples
Author(s): Daisuke Sato , Hiroyuki Nomura
autogenerated on Mon Oct 2 2023 02:39:27