carm 0.0.20250812__py3-none-any.whl → 0.0.20250815__py3-none-any.whl
This diff represents the content of publicly available package versions that have been released to one of the supported registries. The information contained in this diff is provided for informational purposes only and reflects changes between package versions as they appear in their respective public registries.
- carm/carm.py +3 -0
- carm-0.0.20250815.dist-info/METADATA +11 -0
- carm-0.0.20250815.dist-info/RECORD +7 -0
- carm-0.0.20250815.dist-info/entry_points.txt +3 -0
- carm/carm_driver.py +0 -303
- carm-0.0.20250812.data/scripts/carm +0 -106
- carm-0.0.20250812.data/scripts/carm_ros2 +0 -94
- carm-0.0.20250812.dist-info/METADATA +0 -9
- carm-0.0.20250812.dist-info/RECORD +0 -10
- carm-0.0.20250812.dist-info/zip-safe +0 -1
- {carm-0.0.20250812.dist-info → carm-0.0.20250815.dist-info}/WHEEL +0 -0
- {carm-0.0.20250812.dist-info → carm-0.0.20250815.dist-info}/top_level.txt +0 -0
carm/carm.py
CHANGED
|
@@ -2,6 +2,7 @@ import websocket
|
|
|
2
2
|
import threading
|
|
3
3
|
import json
|
|
4
4
|
import uuid
|
|
5
|
+
import time
|
|
5
6
|
|
|
6
7
|
class Carm:
|
|
7
8
|
def __init__(self, addr = "ws://100.84.147.120:8090"):
|
|
@@ -42,6 +43,8 @@ class Carm:
|
|
|
42
43
|
"type":"version"})
|
|
43
44
|
|
|
44
45
|
def set_ready(self):
|
|
46
|
+
while self.state is None:
|
|
47
|
+
time.sleep(0.1)
|
|
45
48
|
arm = self.state["arm"][0]
|
|
46
49
|
if arm["fsm_state"] == "POSITION" or arm["fsm_state"] == "MIT":
|
|
47
50
|
return True
|
|
@@ -0,0 +1,11 @@
|
|
|
1
|
+
Metadata-Version: 2.1
|
|
2
|
+
Name: carm
|
|
3
|
+
Version: 0.0.20250815
|
|
4
|
+
Summary: Python interface for cvte arm.
|
|
5
|
+
Author-email: Yong Zhao <zhaoyong11933@cvte.com>
|
|
6
|
+
Classifier: Programming Language :: Python :: 3
|
|
7
|
+
Classifier: Programming Language :: Python :: Implementation :: CPython
|
|
8
|
+
Classifier: Programming Language :: Python :: Implementation :: PyPy
|
|
9
|
+
Requires-Python: >=3.6
|
|
10
|
+
Requires-Dist: websocket-client
|
|
11
|
+
|
|
@@ -0,0 +1,7 @@
|
|
|
1
|
+
carm/__init__.py,sha256=lfNjXYpO8FjQVunCqiaUzjsNUnyuhcyO8Je0ixh1RJY,24
|
|
2
|
+
carm/carm.py,sha256=cx04M6b5XyQpB8Xw-9sycwmoE4fKi3tBqGjmCmtABAc,10404
|
|
3
|
+
carm-0.0.20250815.dist-info/METADATA,sha256=wZxNVuffF6HYb3_Qm7giI5qpBFU14luJ1XE0XLMddOw,389
|
|
4
|
+
carm-0.0.20250815.dist-info/WHEEL,sha256=iAkIy5fosb7FzIOwONchHf19Qu7_1wCWyFNR5gu9nU0,91
|
|
5
|
+
carm-0.0.20250815.dist-info/entry_points.txt,sha256=N8dt2p7PK_49n8YkzKy8tymcvKS7JEH9Ob6i093vEUg,62
|
|
6
|
+
carm-0.0.20250815.dist-info/top_level.txt,sha256=nZ1bTssUAnAqc2CMka3erGx_2LsdZrSkqtjNf9Ce_d8,5
|
|
7
|
+
carm-0.0.20250815.dist-info/RECORD,,
|
carm/carm_driver.py
DELETED
|
@@ -1,303 +0,0 @@
|
|
|
1
|
-
import websocket
|
|
2
|
-
import threading
|
|
3
|
-
import json
|
|
4
|
-
import uuid
|
|
5
|
-
|
|
6
|
-
class Carm:
|
|
7
|
-
def __init__(self, addr = "ws://100.84.147.120:8090"):
|
|
8
|
-
self.state = None
|
|
9
|
-
self.last_msg = None
|
|
10
|
-
self.ws = websocket.WebSocketApp(
|
|
11
|
-
addr, # 测试用的公开WebSocket服务
|
|
12
|
-
on_open = lambda ws: self.on_open(ws),
|
|
13
|
-
on_close = lambda ws, code, close_msg: self.on_close(ws, code, close_msg),
|
|
14
|
-
on_message= lambda ws, msg: self.on_message(ws, msg),
|
|
15
|
-
)
|
|
16
|
-
|
|
17
|
-
self.ops = {
|
|
18
|
-
"webSendRobotState": lambda msg: self.cbk_status(msg),
|
|
19
|
-
"taskFinished": lambda msg: self.cbk_taskfinish(msg),
|
|
20
|
-
"onCarmError": lambda msg: print("Error:", msg)
|
|
21
|
-
}
|
|
22
|
-
self.res_pool = {}
|
|
23
|
-
self.task_pool = {}
|
|
24
|
-
|
|
25
|
-
self.reader = threading.Thread(target=self.recv_loop).start()
|
|
26
|
-
self.open_ready = threading.Event()
|
|
27
|
-
self.open_ready.wait()
|
|
28
|
-
self.limit = self.get_limits()["params"]
|
|
29
|
-
|
|
30
|
-
self.set_ready()
|
|
31
|
-
|
|
32
|
-
@property
|
|
33
|
-
def version(self):
|
|
34
|
-
return self.request({"command":"getArmIntrinsicProperties",
|
|
35
|
-
"arm_index":0,
|
|
36
|
-
"type":"version"})
|
|
37
|
-
|
|
38
|
-
|
|
39
|
-
def get_limits(self):
|
|
40
|
-
return self.request({"command":"getJointParams",
|
|
41
|
-
"arm_index":0,
|
|
42
|
-
"type":"version"})
|
|
43
|
-
|
|
44
|
-
def set_ready(self):
|
|
45
|
-
arm = self.state["arm"][0]
|
|
46
|
-
if arm["fsm_state"] == "POSITION" or arm["fsm_state"] == "MIT":
|
|
47
|
-
return True
|
|
48
|
-
|
|
49
|
-
if arm["fsm_state"] == "ERROR":
|
|
50
|
-
self.clean_carm_error()
|
|
51
|
-
|
|
52
|
-
if arm["fsm_state"] == "IDLE":
|
|
53
|
-
self.set_servo_enable(True)
|
|
54
|
-
|
|
55
|
-
return self.set_control_mode(1)
|
|
56
|
-
|
|
57
|
-
def set_servo_enable(self, enable=True):
|
|
58
|
-
return self.request({"command":"setServoEnable",
|
|
59
|
-
"arm_index":0,
|
|
60
|
-
"enable":enable})
|
|
61
|
-
|
|
62
|
-
def set_control_mode(self, mode=1):
|
|
63
|
-
return self.request({"command":"setControlMode",
|
|
64
|
-
"arm_index":0,
|
|
65
|
-
"mode":mode})
|
|
66
|
-
|
|
67
|
-
def set_end_effector(self, pos, tau):
|
|
68
|
-
pos = self.__clip(pos, 0, 0.08)
|
|
69
|
-
tau = self.__clip(tau, 0, 9)
|
|
70
|
-
|
|
71
|
-
return self.request({"command":"setEffectorCtr",
|
|
72
|
-
"arm_index":0,
|
|
73
|
-
"pos": pos,
|
|
74
|
-
"tau": tau})
|
|
75
|
-
|
|
76
|
-
def get_tool_coordinate(self, tool):
|
|
77
|
-
return self.request({"command":"getCoordinate",
|
|
78
|
-
"arm_index":0,
|
|
79
|
-
"type": "tool",
|
|
80
|
-
"index": tool})
|
|
81
|
-
|
|
82
|
-
|
|
83
|
-
def set_collision_config(self, flag = True, level = 10):
|
|
84
|
-
return self.request({"command":"setCollisionConfig",
|
|
85
|
-
"arm_index":0,
|
|
86
|
-
"flag": flag,
|
|
87
|
-
"level": level})
|
|
88
|
-
|
|
89
|
-
def stop(self, type=0):
|
|
90
|
-
stop_id = ["SIG_ARM_PAUSE", "SIG_ARM_STOP",
|
|
91
|
-
"SIG_ARM_DISABLE","SIG_EMERGENCY_STOP"]
|
|
92
|
-
return self.request({"command":"stopSignals",
|
|
93
|
-
"arm_index":0,
|
|
94
|
-
"stop_id": stop_id[type],
|
|
95
|
-
"step_cnt":5})
|
|
96
|
-
|
|
97
|
-
def stop_task(self, at_once=False):
|
|
98
|
-
return self.request({"command":"stopSignals",
|
|
99
|
-
"arm_index":0,
|
|
100
|
-
"stop_id": "SIG_TASK_STOP",
|
|
101
|
-
"stop_at_once": at_once})
|
|
102
|
-
|
|
103
|
-
def recover(self):
|
|
104
|
-
return self.request({"command":"stopSignals",
|
|
105
|
-
"arm_index":0,
|
|
106
|
-
"stop_id": "SIG_ARM_RECOVER",
|
|
107
|
-
"step_cnt": 5})
|
|
108
|
-
|
|
109
|
-
def clean_carm_error(self):
|
|
110
|
-
return self.request({"command":"setControllerErrorReset",
|
|
111
|
-
"arm_index":0})
|
|
112
|
-
|
|
113
|
-
def set_speed_level(self, level, response_level):
|
|
114
|
-
return self.request({"command":"setSpeedLevel",
|
|
115
|
-
"arm_index":0,
|
|
116
|
-
"level":level,
|
|
117
|
-
"response_level":response_level})
|
|
118
|
-
|
|
119
|
-
def set_debug(self, flag):
|
|
120
|
-
return self.request({"command":"setDebugMode",
|
|
121
|
-
"arm_index":0,
|
|
122
|
-
"trigger":flag})
|
|
123
|
-
|
|
124
|
-
def get_urdf(self):
|
|
125
|
-
return self.request({"command":"getArmIntrinsicProperties",
|
|
126
|
-
"arm_index":0,
|
|
127
|
-
"type":"urdf"})
|
|
128
|
-
@property
|
|
129
|
-
def joint_pos(self):
|
|
130
|
-
return self.state["arm"][0]["reality"]["pose"]
|
|
131
|
-
|
|
132
|
-
@property
|
|
133
|
-
def joint_vel(self):
|
|
134
|
-
return self.state["arm"][0]["reality"]["vel"]
|
|
135
|
-
|
|
136
|
-
@property
|
|
137
|
-
def joint_tau(self):
|
|
138
|
-
return self.state["arm"][0]["reality"]["torque"]
|
|
139
|
-
|
|
140
|
-
@property
|
|
141
|
-
def cart_pose(self):
|
|
142
|
-
return self.state["arm"][0]["pose"]
|
|
143
|
-
|
|
144
|
-
@property
|
|
145
|
-
def gripper_state(self):
|
|
146
|
-
return self.state["arm"][0]["gripper"]
|
|
147
|
-
|
|
148
|
-
def clip_joints(self, joints):
|
|
149
|
-
lower = self.limit['limit_lower']
|
|
150
|
-
upper = self.limit["limit_upper"]
|
|
151
|
-
for i,v in enumerate(joints):
|
|
152
|
-
joints[i] = self.__clip(v, lower[i], upper[i])
|
|
153
|
-
return joints
|
|
154
|
-
|
|
155
|
-
def track_joint(self, pos, end_effector = -1):
|
|
156
|
-
pos = self.clip_joints(pos)
|
|
157
|
-
req = {"command":"trajectoryTrackingTasks",
|
|
158
|
-
"task_id":"TASK_TRACKING",
|
|
159
|
-
"arm_index":0,
|
|
160
|
-
"point_type":{"space":0},
|
|
161
|
-
"data":{"way_point": pos}}
|
|
162
|
-
|
|
163
|
-
if end_effector >= 0:
|
|
164
|
-
req["data"]["eeffe_point"] = end_effector
|
|
165
|
-
|
|
166
|
-
return self.request(req)
|
|
167
|
-
|
|
168
|
-
def track_pose(self, pos, end_effector = -1):
|
|
169
|
-
req = {"command":"trajectoryTrackingTasks",
|
|
170
|
-
"task_id":"TASK_TRACKING",
|
|
171
|
-
"arm_index":0,
|
|
172
|
-
"point_type":{"space":1},
|
|
173
|
-
"data":{"way_point": pos}}
|
|
174
|
-
|
|
175
|
-
if end_effector > 0:
|
|
176
|
-
req["data"]["eeffe_point"] = end_effector
|
|
177
|
-
|
|
178
|
-
return self.request(req)
|
|
179
|
-
|
|
180
|
-
def move_joint(self, pos, tm=-1, sync=True, user=0, tool=0):
|
|
181
|
-
pos = self.clip_joints(pos)
|
|
182
|
-
|
|
183
|
-
res = self.request({"command":"webRecieveTasks",
|
|
184
|
-
"task_id":"TASK_MOVJ",
|
|
185
|
-
"task_level":"Task_General",
|
|
186
|
-
"arm_index":0,
|
|
187
|
-
"point_type":{"space":0},
|
|
188
|
-
"data":{"user":user,"tool":tool, "target_pos": pos, "speed":100}})
|
|
189
|
-
|
|
190
|
-
if sync and res["recv"]=="Task_Recieve":
|
|
191
|
-
self.wait_task(res["task_key"])
|
|
192
|
-
|
|
193
|
-
return res
|
|
194
|
-
|
|
195
|
-
def move_pose(self, pos, tm=-1, sync=True, user=0, tool=0):
|
|
196
|
-
res = self.request({"command":"webRecieveTasks",
|
|
197
|
-
"task_id":"TASK_MOVJ",
|
|
198
|
-
"task_level":"Task_General",
|
|
199
|
-
"arm_index":0,
|
|
200
|
-
"point_type":{"space":1},
|
|
201
|
-
"data":{"user":user,"tool":tool, "target_pos": pos, "speed":100}})
|
|
202
|
-
|
|
203
|
-
if sync and res["recv"]=="Task_Recieve":
|
|
204
|
-
self.wait_task(res["task_key"])
|
|
205
|
-
|
|
206
|
-
return res
|
|
207
|
-
|
|
208
|
-
def wait_task(self, task_key):
|
|
209
|
-
event = threading.Event()
|
|
210
|
-
self.task_pool[task_key] = {"event":event}
|
|
211
|
-
event.wait()
|
|
212
|
-
self.task_pool.pop(task_key)
|
|
213
|
-
|
|
214
|
-
def move_joint_traj(self, target_traj, gripper_pos = [], stamps = [], is_sync=True):
|
|
215
|
-
if len(stamps) != len(target_traj): # as soon as possible
|
|
216
|
-
return self.move_toppra(target_traj, gripper_pos, 100, is_sync)
|
|
217
|
-
else:
|
|
218
|
-
return self.move_pvt(target_traj, gripper_pos, stamps, is_sync)
|
|
219
|
-
|
|
220
|
-
def move_pose_traj(self, target_traj, gripper_pos = [], stamps = [], is_sync=True):
|
|
221
|
-
if len(stamps) != len(target_traj): # as soon as possible
|
|
222
|
-
return self.move_toppra(target_traj, gripper_pos, 100, is_sync)
|
|
223
|
-
else:
|
|
224
|
-
return self.move_pvt(target_traj, gripper_pos, stamps, is_sync)
|
|
225
|
-
|
|
226
|
-
def move_toppra(self, target_traj, gripper_pos = [], speed = [], is_sync=True):
|
|
227
|
-
pass # TODO
|
|
228
|
-
|
|
229
|
-
def move_pvt(self, target_traj, gripper_pos = [], stamps = [], is_sync=True):
|
|
230
|
-
pass # TODO
|
|
231
|
-
|
|
232
|
-
def invK(self, cart_pose, ref_joints, user=0, tool=0):
|
|
233
|
-
if not type(cart_pose[0]) is list:
|
|
234
|
-
cart_pose = [cart_pose, ]
|
|
235
|
-
assert(len(cart_pose) == len(ref_joints))
|
|
236
|
-
return self.request({"command":"getKinematics",
|
|
237
|
-
"task_id":"inverse",
|
|
238
|
-
"arm_index":0,
|
|
239
|
-
"data":{"user":user,"tool":tool,"point_cnt":len(cart_pose)}})
|
|
240
|
-
|
|
241
|
-
def request(self, req):
|
|
242
|
-
event = threading.Event()
|
|
243
|
-
task_key = str(uuid.uuid4())
|
|
244
|
-
req["task_key"] = task_key
|
|
245
|
-
self.res_pool[task_key] = {"req":req,"event":event}
|
|
246
|
-
|
|
247
|
-
self.send(req)
|
|
248
|
-
|
|
249
|
-
event.wait()
|
|
250
|
-
return self.res_pool.pop(task_key)["res"]
|
|
251
|
-
|
|
252
|
-
def send(self, msg):
|
|
253
|
-
self.ws.send(json.dumps(msg))
|
|
254
|
-
|
|
255
|
-
def cbk_status(self, message):
|
|
256
|
-
self.state = message
|
|
257
|
-
|
|
258
|
-
def cbk_taskfinish(self, message):
|
|
259
|
-
task = message["task_key"]
|
|
260
|
-
self.task_pool[task]["event"].set()
|
|
261
|
-
|
|
262
|
-
def on_open(self, ws):
|
|
263
|
-
self.open_ready.set()
|
|
264
|
-
print("连接成功")
|
|
265
|
-
|
|
266
|
-
def on_close(self, ws, code, close_msg):
|
|
267
|
-
print("连接断开",code, close_msg)
|
|
268
|
-
|
|
269
|
-
def on_message(self, ws, message):
|
|
270
|
-
msg = json.loads(message)
|
|
271
|
-
self.last_msg = msg
|
|
272
|
-
cmd = msg["command"]
|
|
273
|
-
op = self.ops.get(cmd, lambda msg: self.response_op(msg))
|
|
274
|
-
op(msg)
|
|
275
|
-
|
|
276
|
-
def response_op(self, res):
|
|
277
|
-
id = res.get("task_key","")
|
|
278
|
-
data = self.res_pool[id]
|
|
279
|
-
data["res"] = res
|
|
280
|
-
data["event"].set() # notify request thread
|
|
281
|
-
|
|
282
|
-
|
|
283
|
-
def recv_loop(self):
|
|
284
|
-
print("Recv loop started.")
|
|
285
|
-
self.ws.run_forever()
|
|
286
|
-
|
|
287
|
-
def __clip(self, value, min_val, max_val):
|
|
288
|
-
return max(min_val, min(value, max_val))
|
|
289
|
-
|
|
290
|
-
if __name__ == "__main__":
|
|
291
|
-
carm = Carm()
|
|
292
|
-
print("version:",carm.version)
|
|
293
|
-
print("limits:", carm.limit)
|
|
294
|
-
print("state:", carm.state)
|
|
295
|
-
|
|
296
|
-
carm.track_joint(carm.joint_pos)
|
|
297
|
-
print(1)
|
|
298
|
-
carm.move_joint(carm.joint_pos)
|
|
299
|
-
print(2)
|
|
300
|
-
carm.track_pose(carm.cart_pose)
|
|
301
|
-
print(3)
|
|
302
|
-
carm.move_pose(carm.cart_pose)
|
|
303
|
-
print(4)
|
|
@@ -1,106 +0,0 @@
|
|
|
1
|
-
#!python
|
|
2
|
-
import time
|
|
3
|
-
import os
|
|
4
|
-
import argparse
|
|
5
|
-
import svar
|
|
6
|
-
import numpy as np
|
|
7
|
-
import carm
|
|
8
|
-
|
|
9
|
-
messenger = svar.load("svar_messenger").messenger
|
|
10
|
-
|
|
11
|
-
class ArmDriver:
|
|
12
|
-
def __init__(self,args):
|
|
13
|
-
self.args = args
|
|
14
|
-
|
|
15
|
-
self.arm = carm.Carm(args.addr)
|
|
16
|
-
if args.mit:
|
|
17
|
-
self.arm.set_control_mode(3)
|
|
18
|
-
else:
|
|
19
|
-
self.arm.set_control_mode(1)
|
|
20
|
-
|
|
21
|
-
self.pub_joint = messenger.advertise(args.joint_topic, 0)
|
|
22
|
-
self.pub_end = messenger.advertise(args.end_topic, 0)
|
|
23
|
-
|
|
24
|
-
self.sub_joint = messenger.subscribe(args.joint_cmd_topic, 0, lambda msg:self.joint_callback(msg))
|
|
25
|
-
self.sub_end = messenger.subscribe(args.end_cmd_topic, 0, lambda msg:self.end_callback(msg))
|
|
26
|
-
|
|
27
|
-
def end_callback(self, msg):
|
|
28
|
-
position = np.frombuffer(msg["position"],dtype=np.float64).tolist()
|
|
29
|
-
self.arm.track_pose(position)
|
|
30
|
-
|
|
31
|
-
def joint_callback(self, msg):
|
|
32
|
-
position = np.frombuffer(msg["position"],dtype=np.float64).tolist()
|
|
33
|
-
self.arm.track_joint(position)
|
|
34
|
-
|
|
35
|
-
def loop(self):
|
|
36
|
-
while True:
|
|
37
|
-
stamp = time.time()
|
|
38
|
-
sec = int(stamp )
|
|
39
|
-
nanosec = int((stamp - sec) * 1e9)
|
|
40
|
-
header = {"stamp": {"sec": sec, "nanosec": nanosec},"frame_id": "base_link"}
|
|
41
|
-
|
|
42
|
-
end_msg = {"header": header, "position": self.arm.cart_pose + [self.arm.gripper_state["gripper_pos"],]}
|
|
43
|
-
joints_msg = {"header": header, "position": self.arm.joint_pos + [self.arm.gripper_state["gripper_pos"],]}
|
|
44
|
-
|
|
45
|
-
self.pub_joint.publish(joints_msg)
|
|
46
|
-
self.pub_end.publish(end_msg)
|
|
47
|
-
|
|
48
|
-
time.sleep(0.005)
|
|
49
|
-
|
|
50
|
-
def send_cmd(args):
|
|
51
|
-
arm = carm.Carm(args.addr,mit=args.mit)
|
|
52
|
-
|
|
53
|
-
cmd = args.cmd
|
|
54
|
-
|
|
55
|
-
if cmd == "disable":
|
|
56
|
-
arm.set_servo_enable(False)
|
|
57
|
-
if cmd == "remote":
|
|
58
|
-
arm.set_control_mode(3)
|
|
59
|
-
|
|
60
|
-
def driver_main(args):
|
|
61
|
-
print("Starting driver mode...")
|
|
62
|
-
|
|
63
|
-
driver = ArmDriver(args)
|
|
64
|
-
|
|
65
|
-
ros2 = svar.load(args.dds)
|
|
66
|
-
transfer = ros2.Transfer({"node": "carm_driver" + args.device,
|
|
67
|
-
"publishers":[[args.joint_topic, "sensor_msgs/msg/JointState",10],
|
|
68
|
-
[args.end_topic, "sensor_msgs/msg/JointState",10],
|
|
69
|
-
],
|
|
70
|
-
"subscriptions":[[args.joint_cmd_topic, "sensor_msgs/msg/JointState",10],
|
|
71
|
-
[args.end_cmd_topic, "sensor_msgs/msg/JointState",10]]})
|
|
72
|
-
|
|
73
|
-
driver.loop()
|
|
74
|
-
|
|
75
|
-
|
|
76
|
-
|
|
77
|
-
# 测试代码
|
|
78
|
-
if __name__ == "__main__":
|
|
79
|
-
parser = argparse.ArgumentParser()
|
|
80
|
-
parser.add_argument("--addr", type=str, default="ws://localhost:8090", help="Device address, including ip and port")
|
|
81
|
-
parser.add_argument("--cmd", type=str, default="", help="Send command instead of start driver, support enable,disable,remote")
|
|
82
|
-
parser.add_argument("--device", type=str, default="carm", help="device name, used as topic prefix")
|
|
83
|
-
parser.add_argument("--dds", type=str, default="svar_messenger_ros2", help="the dds plugin, default is ros2, options: svar_zbus, svar_lcm")
|
|
84
|
-
parser.add_argument("--mit", action="store_true", help="Enable mit mode")
|
|
85
|
-
parser.add_argument("--joint_topic", type=str, default="", help="the joints status topic")
|
|
86
|
-
parser.add_argument("--end_topic", type=str, default="", help="the joints status topic")
|
|
87
|
-
parser.add_argument("--joint_cmd_topic", type=str, default="", help="the joints cmd topic")
|
|
88
|
-
parser.add_argument("--end_cmd_topic", type=str, default="", help="the end cmd topic")
|
|
89
|
-
|
|
90
|
-
args = parser.parse_args()
|
|
91
|
-
|
|
92
|
-
if args.joint_topic == "":
|
|
93
|
-
args.joint_topic = "/"+args.device + "/joints"
|
|
94
|
-
if args.end_topic == "":
|
|
95
|
-
args.end_topic = "/"+args.device + "/end"
|
|
96
|
-
if args.joint_cmd_topic == "":
|
|
97
|
-
args.joint_cmd_topic = "/"+args.device + "/joints_cmd"
|
|
98
|
-
if args.end_cmd_topic == "":
|
|
99
|
-
args.end_cmd_topic = "/"+args.device + "/end_cmd"
|
|
100
|
-
|
|
101
|
-
if args.cmd == "":
|
|
102
|
-
driver_main(args)
|
|
103
|
-
else:
|
|
104
|
-
send_cmd(args)
|
|
105
|
-
|
|
106
|
-
|
|
@@ -1,94 +0,0 @@
|
|
|
1
|
-
#!python
|
|
2
|
-
import rclpy
|
|
3
|
-
from rclpy.node import Node
|
|
4
|
-
import time
|
|
5
|
-
import argparse
|
|
6
|
-
|
|
7
|
-
from std_msgs.msg import String, Bool, Int16MultiArray, MultiArrayLayout, MultiArrayDimension, Int8
|
|
8
|
-
from geometry_msgs.msg import Point, Pose, PoseArray
|
|
9
|
-
from sensor_msgs.msg import JointState
|
|
10
|
-
from example_interfaces.srv import AddTwoInts
|
|
11
|
-
import carm
|
|
12
|
-
import threading
|
|
13
|
-
import numpy as np
|
|
14
|
-
|
|
15
|
-
class ArmDriver(Node):
|
|
16
|
-
def __init__(self,args):
|
|
17
|
-
super().__init__('carm_'+args.device)
|
|
18
|
-
self.args = args
|
|
19
|
-
|
|
20
|
-
self.arm = carm.Carm(args.addr)
|
|
21
|
-
if args.mit:
|
|
22
|
-
self.arm.set_control_mode(3)
|
|
23
|
-
else:
|
|
24
|
-
self.arm.set_control_mode(1)
|
|
25
|
-
|
|
26
|
-
|
|
27
|
-
print("version:",self.arm.version)
|
|
28
|
-
print("limits:", self.arm.limit)
|
|
29
|
-
print("state:", self.arm.state)
|
|
30
|
-
|
|
31
|
-
self.pub_joint = self.create_publisher(JointState, args.joint_topic, 10)
|
|
32
|
-
self.pub_end = self.create_publisher(JointState, args.end_topic, 10)
|
|
33
|
-
|
|
34
|
-
self.sub_joint = self.create_subscription(JointState, args.joint_cmd_topic, self.joint_callback, 10)
|
|
35
|
-
self.sub_end = self.create_subscription(JointState, args.end_cmd_topic, self.end_callback, 10)
|
|
36
|
-
|
|
37
|
-
self.worker = threading.Thread(target=self.loop).start()
|
|
38
|
-
|
|
39
|
-
def end_callback(self, msg):
|
|
40
|
-
self.arm.track_pose(list(msg.position))
|
|
41
|
-
|
|
42
|
-
def joint_callback(self, msg):
|
|
43
|
-
self.arm.track_joint(list(msg.position))
|
|
44
|
-
|
|
45
|
-
def loop(self):
|
|
46
|
-
while True:
|
|
47
|
-
joint_msg = JointState() # list of string
|
|
48
|
-
joint_msg.header.stamp = self.get_clock().now().to_msg()
|
|
49
|
-
joint_msg.position = self.arm.joint_pos
|
|
50
|
-
joint_msg.velocity = self.arm.joint_vel
|
|
51
|
-
joint_msg.effort = self.arm.joint_tau
|
|
52
|
-
joint_msg.position.append(self.arm.gripper_state["gripper_pos"])
|
|
53
|
-
self.pub_joint.publish(joint_msg)
|
|
54
|
-
|
|
55
|
-
|
|
56
|
-
end_msg = JointState() # list of string
|
|
57
|
-
end_msg.header.stamp = self.get_clock().now().to_msg()
|
|
58
|
-
end_msg.position = np.array(self.arm.cart_pose).tolist()
|
|
59
|
-
end_msg.position.append(self.arm.gripper_state["gripper_pos"])
|
|
60
|
-
self.pub_end.publish(end_msg)
|
|
61
|
-
|
|
62
|
-
time.sleep(0.005)
|
|
63
|
-
|
|
64
|
-
# 测试代码
|
|
65
|
-
if __name__ == "__main__":
|
|
66
|
-
parser = argparse.ArgumentParser()
|
|
67
|
-
parser.add_argument("--addr", type=str, default="ws://localhost:8090", help="Device address, including ip and port")
|
|
68
|
-
parser.add_argument("--device", type=str, default="carm", help="device name, used as topic prefix")
|
|
69
|
-
parser.add_argument("--dds", type=str, default="svar_messenger_ros2", help="the dds plugin, default is ros2, options: svar_zbus, svar_lcm")
|
|
70
|
-
parser.add_argument("--mit", action="store_true", help="Enable mit mode")
|
|
71
|
-
parser.add_argument("--joint_topic", type=str, default="", help="the joints status topic")
|
|
72
|
-
parser.add_argument("--end_topic", type=str, default="", help="the joints status topic")
|
|
73
|
-
parser.add_argument("--joint_cmd_topic", type=str, default="", help="the joints cmd topic")
|
|
74
|
-
parser.add_argument("--end_cmd_topic", type=str, default="", help="the end cmd topic")
|
|
75
|
-
|
|
76
|
-
args = parser.parse_args()
|
|
77
|
-
|
|
78
|
-
if args.joint_topic == "":
|
|
79
|
-
args.joint_topic = "/"+args.device + "/joints"
|
|
80
|
-
if args.end_topic == "":
|
|
81
|
-
args.end_topic = "/"+args.device + "/end"
|
|
82
|
-
if args.joint_cmd_topic == "":
|
|
83
|
-
args.joint_cmd_topic = "/"+args.device + "/joints_cmd"
|
|
84
|
-
if args.end_cmd_topic == "":
|
|
85
|
-
args.end_cmd_topic = "/"+args.device + "/end_cmd"
|
|
86
|
-
|
|
87
|
-
|
|
88
|
-
rclpy.init(args=None)
|
|
89
|
-
node = ArmDriver(args)
|
|
90
|
-
rclpy.spin(node)
|
|
91
|
-
node.destroy_node()
|
|
92
|
-
rclpy.shutdown()
|
|
93
|
-
|
|
94
|
-
|
|
@@ -1,10 +0,0 @@
|
|
|
1
|
-
carm/__init__.py,sha256=lfNjXYpO8FjQVunCqiaUzjsNUnyuhcyO8Je0ixh1RJY,24
|
|
2
|
-
carm/carm.py,sha256=8EpL0iaWyfRWsKmmh_K2qtxqNUHHkU0uoDZRfctGSfY,10330
|
|
3
|
-
carm/carm_driver.py,sha256=fT6UYpJEr0kcmPQcXvbCaAw27_770iqNs64OrscwUdU,10393
|
|
4
|
-
carm-0.0.20250812.data/scripts/carm,sha256=kWcTgUciXtd3cMA3w__cZMVNe4QURi-xHEx8ob2vWnA,4088
|
|
5
|
-
carm-0.0.20250812.data/scripts/carm_ros2,sha256=MfzWv6-orDIpFJQ4ctmP1NBYg135qpc61gIraL7hPP0,3683
|
|
6
|
-
carm-0.0.20250812.dist-info/METADATA,sha256=ahKVvXQf-2daRSrO_k4za2spQ1yTD_sTlljskAyJxn4,214
|
|
7
|
-
carm-0.0.20250812.dist-info/WHEEL,sha256=iAkIy5fosb7FzIOwONchHf19Qu7_1wCWyFNR5gu9nU0,91
|
|
8
|
-
carm-0.0.20250812.dist-info/top_level.txt,sha256=nZ1bTssUAnAqc2CMka3erGx_2LsdZrSkqtjNf9Ce_d8,5
|
|
9
|
-
carm-0.0.20250812.dist-info/zip-safe,sha256=AbpHGcgLb-kRsJGnwFEktk7uzpZOCcBY74-YBdrKVGs,1
|
|
10
|
-
carm-0.0.20250812.dist-info/RECORD,,
|
|
@@ -1 +0,0 @@
|
|
|
1
|
-
|
|
File without changes
|
|
File without changes
|